diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt index 9bfe4b327..f9908b5f4 100644 --- a/.github/ci/packages.apt +++ b/.github/ci/packages.apt @@ -3,6 +3,7 @@ libavdevice-dev libavformat-dev libavutil-dev libfreeimage-dev +libgdal-dev libgts-dev libignition-cmake2-dev libignition-math7-dev diff --git a/CMakeLists.txt b/CMakeLists.txt index da71892bb..a9d507c8e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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}) #-------------------------------------- @@ -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) @@ -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 diff --git a/Migration.md b/Migration.md index 69f1bb4bb..7b9385355 100644 --- a/Migration.md +++ b/Migration.md @@ -5,6 +5,20 @@ 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 + ## Ignition Common 3.X to 4.X ### Modifications @@ -72,4 +86,3 @@ 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. - diff --git a/geospatial/include/ignition/common/CMakeLists.txt b/geospatial/include/ignition/common/CMakeLists.txt new file mode 100644 index 000000000..7155438eb --- /dev/null +++ b/geospatial/include/ignition/common/CMakeLists.txt @@ -0,0 +1,2 @@ + +ign_install_all_headers(COMPONENT geospatial) diff --git a/graphics/include/ignition/common/Dem.hh b/geospatial/include/ignition/common/Dem.hh similarity index 90% rename from graphics/include/ignition/common/Dem.hh rename to geospatial/include/ignition/common/Dem.hh index ff83c0dd8..2d251b7ec 100644 --- a/graphics/include/ignition/common/Dem.hh +++ b/geospatial/include/ignition/common/Dem.hh @@ -18,18 +18,17 @@ #define IGNITION_COMMON_DEM_HH_ #include +#include +#include + #include #include +#include #include #include -#ifdef HAVE_GDAL -# include -# include - -# include namespace ignition { @@ -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. @@ -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 @@ -120,7 +121,8 @@ namespace ignition /// \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; @@ -130,6 +132,9 @@ 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) @@ -137,4 +142,3 @@ namespace ignition } } #endif -#endif diff --git a/graphics/include/ignition/common/HeightmapData.hh b/geospatial/include/ignition/common/HeightmapData.hh similarity index 84% rename from graphics/include/ignition/common/HeightmapData.hh rename to geospatial/include/ignition/common/HeightmapData.hh index 22eeb4945..a67b1135a 100644 --- a/graphics/include/ignition/common/HeightmapData.hh +++ b/geospatial/include/ignition/common/HeightmapData.hh @@ -17,6 +17,7 @@ #ifndef IGNITION_COMMON_HEIGHTMAPDATA_HH_ #define IGNITION_COMMON_HEIGHTMAPDATA_HH_ +#include #include #include #include @@ -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; }; } } diff --git a/graphics/include/ignition/common/ImageHeightmap.hh b/geospatial/include/ignition/common/ImageHeightmap.hh similarity index 98% rename from graphics/include/ignition/common/ImageHeightmap.hh rename to geospatial/include/ignition/common/ImageHeightmap.hh index 43a1bccc8..5ee7431e8 100644 --- a/graphics/include/ignition/common/ImageHeightmap.hh +++ b/geospatial/include/ignition/common/ImageHeightmap.hh @@ -49,8 +49,7 @@ namespace ignition const ignition::math::Vector3d &_scale, bool _flipY, std::vector &_heights); - /// \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. diff --git a/geospatial/src/CMakeLists.txt b/geospatial/src/CMakeLists.txt new file mode 100644 index 000000000..6975e86fc --- /dev/null +++ b/geospatial/src/CMakeLists.txt @@ -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}) diff --git a/graphics/src/Dem.cc b/geospatial/src/Dem.cc similarity index 69% rename from graphics/src/Dem.cc rename to geospatial/src/Dem.cc index ad52f023c..eb9318555 100644 --- a/graphics/src/Dem.cc +++ b/geospatial/src/Dem.cc @@ -15,13 +15,10 @@ * */ #include +#include -#ifdef HAVE_GDAL -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wfloat-equal" -# include -# pragma GCC diagnostic pop -#endif +#include +#include #include "ignition/common/Console.hh" #include "ignition/common/Dem.hh" @@ -30,8 +27,6 @@ using namespace ignition; using namespace common; -#ifdef HAVE_GDAL - class ignition::common::Dem::Implementation { /// \brief A set of associated raster bands. @@ -57,6 +52,9 @@ class ignition::common::Dem::Implementation /// \brief DEM data converted to be OGRE-compatible. public: std::vector demData; + + /// \brief Full filename used to load the dem. + public: std::string filename; }; ////////////////////////////////////////////////// @@ -89,12 +87,13 @@ int Dem::Load(const std::string &_filename) // Sanity check std::string fullName = _filename; if (!exists(findFilePath(fullName))) - fullName = common::find_file(_filename); + fullName = common::findFile(_filename); + + this->dataPtr->filename = fullName; if (!exists(findFilePath(fullName))) { - gzerr << "Unable to open DEM file[" << _filename - << "], check your GAZEBO_RESOURCE_PATH settings." << std::endl; + ignerr << "Unable to find DEM file[" << _filename << "]." << std::endl; return -1; } @@ -103,25 +102,25 @@ int Dem::Load(const std::string &_filename) if (this->dataPtr->dataSet == nullptr) { - gzerr << "Unable to open DEM file[" << fullName - << "]. Format not recognised as a supported dataset." << std::endl; + ignerr << "Unable to open DEM file[" << fullName + << "]. Format not recognized as a supported dataset." << std::endl; return -1; } - int nBands = this->dataPtr->dataSet->RasterCount(); + int nBands = this->dataPtr->dataSet->GetRasterCount(); if (nBands != 1) { - gzerr << "Unsupported number of bands in file [" << fullName + "]. Found " + ignerr << "Unsupported number of bands in file [" << fullName + "]. Found " << nBands << " but only 1 is a valid value." << std::endl; return -1; } // Set the pointer to the band - this->dataPtr->band = this->dataPtr->dataSet->RasterBand(1); + this->dataPtr->band = this->dataPtr->dataSet->GetRasterBand(1); // Raster width and height - xSize = this->dataPtr->dataSet->RasterXSize(); - ySize = this->dataPtr->dataSet->RasterYSize(); + xSize = this->dataPtr->dataSet->GetRasterXSize(); + ySize = this->dataPtr->dataSet->GetRasterYSize(); // Corner coordinates upLeftX = 0.0; @@ -132,9 +131,15 @@ int Dem::Load(const std::string &_filename) lowLeftY = ySize; // Calculate the georeferenced coordinates of the terrain corners - this->GeoReference(upLeftX, upLeftY, upLeftLat, upLeftLong); - this->GeoReference(upRightX, upRightY, upRightLat, upRightLong); - this->GeoReference(lowLeftX, lowLeftY, lowLeftLat, lowLeftLong); + if (!this->GeoReference(upLeftX, upLeftY, upLeftLat, upLeftLong) + || !this->GeoReference(upRightX, upRightY, upRightLat, upRightLong) + || !this->GeoReference(lowLeftX, lowLeftY, lowLeftLat, lowLeftLong)) + { + ignerr << "Failed to automatically compute DEM size. " + << "Please use the element to manually set DEM size." + << std::endl; + return -1; + } // Set the world width and height this->dataPtr->worldWidth = @@ -161,12 +166,38 @@ int Dem::Load(const std::string &_filename) if (this->LoadData() != 0) return -1; - // Set the min/max heights - this->dataPtr->minElevation = *std::min_element(&this->dataPtr->demData[0], - &this->dataPtr->demData[0] + this->dataPtr->side * this->dataPtr->side); - this->dataPtr->maxElevation = *std::max_element(&this->dataPtr->demData[0], - &this->dataPtr->demData[0] + this->dataPtr->side * this->dataPtr->side); + // Check for nodata value in dem data. This is used when computing the + // min elevation. If nodata value is not defined, we assume it will be one + // of the commonly used values such as -9999, -32768, etc. + // See https://desktop.arcgis.com/en/arcmap/10.8/manage-data/raster-and-images/nodata-in-raster-datasets.htm + // For simplicity, we will treat values <= -9999 as nodata values and + // ignore them when computing the min elevation. + int validNoData = 0; + const double defaultNoDataValue = -9999; + double noDataValue = this->dataPtr->band->GetNoDataValue(&validNoData); + if (validNoData <= 0) + noDataValue = defaultNoDataValue; + + double min = ignition::math::MAX_D; + double max = -ignition::math::MAX_D; + for (auto d : this->dataPtr->demData) + { + if (d > noDataValue) + { + if (d < min) + min = d; + if (d > max) + max = d; + } + } + if (ignition::math::equal(min, ignition::math::MAX_D) || + ignition::math::equal(max, -ignition::math::MAX_D)) + { + ignwarn << "DEM is composed of 'nodata' values!" << std::endl; + } + this->dataPtr->minElevation = min; + this->dataPtr->maxElevation = max; return 0; } @@ -175,9 +206,10 @@ double Dem::Elevation(double _x, double _y) { if (_x >= this->Width() || _y >= this->Height()) { - gzthrow("Illegal coordinates. You are asking for the elevation in (" << - _x << "," << _y << ") but the terrain is [" << this->Width() << - " x " << this->Height() << "]\n"); + ignerr << "Illegal coordinates. You are asking for the elevation in (" + << _x << "," << _y << ") but the terrain is [" + << this->Width() << " x " << this->Height() << "]" << std::endl; + return std::numeric_limits::infinity(); } return this->dataPtr->demData.at(_y * this->Width() + _x); @@ -196,11 +228,11 @@ float Dem::MaxElevation() const } ////////////////////////////////////////////////// -void Dem::GeoReference(double _x, double _y, +bool Dem::GeoReference(double _x, double _y, ignition::math::Angle &_latitude, ignition::math::Angle &_longitude) const { double geoTransf[6]; - if (this->dataPtr->dataSet->GeoTransform(geoTransf) == CE_None) + if (this->dataPtr->dataSet->GetGeoTransform(geoTransf) == CE_None) { OGRSpatialReference sourceCs; OGRSpatialReference targetCs; @@ -208,26 +240,40 @@ void Dem::GeoReference(double _x, double _y, double xGeoDeg, yGeoDeg; // Transform the terrain's coordinate system to WGS84 - char *importString = strdup(this->dataPtr->dataSet->ProjectionRef()); + const char *importString + = strdup(this->dataPtr->dataSet->GetProjectionRef()); sourceCs.importFromWkt(&importString); targetCs.SetWellKnownGeogCS("WGS84"); cT = OGRCreateCoordinateTransformation(&sourceCs, &targetCs); + if (nullptr == cT) + { + ignerr << "Unable to transform terrain coordinate system to WGS84 for " + << "coordinates (" << _x << "," << _y << ")" << std::endl; + OCTDestroyCoordinateTransformation(cT); + return false; + } xGeoDeg = geoTransf[0] + _x * geoTransf[1] + _y * geoTransf[2]; yGeoDeg = geoTransf[3] + _x * geoTransf[4] + _y * geoTransf[5]; cT->Transform(1, &xGeoDeg, &yGeoDeg); - _latitude.Degree(yGeoDeg); - _longitude.Degree(xGeoDeg); + _latitude.SetDegree(yGeoDeg); + _longitude.SetDegree(xGeoDeg); + + OCTDestroyCoordinateTransformation(cT); } else - gzthrow("Unable to obtain the georeferenced values for coordinates (" - << _x << "," << _y << ")\n"); + { + ignerr << "Unable to obtain the georeferenced values for coordinates (" + << _x << "," << _y << ")" << std::endl; + return false; + } + return true; } ////////////////////////////////////////////////// -void Dem::GeoReferenceOrigin(ignition::math::Angle &_latitude, +bool Dem::GeoReferenceOrigin(ignition::math::Angle &_latitude, ignition::math::Angle &_longitude) const { return this->GeoReference(0, 0, _latitude, _longitude); @@ -265,7 +311,7 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize, { if (_subSampling <= 0) { - gzerr << "Illegal subsampling value (" << _subSampling << ")\n"; + ignerr << "Illegal subsampling value (" << _subSampling << ")\n"; return; } @@ -299,8 +345,8 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize, double px4 = this->dataPtr->demData[y2 * this->dataPtr->side + x2]; float h2 = (px3 - ((px3 - px4) * dx)); - float h = (h1 - ((h1 - h2) * dy) - std::max(0.0f, - this->MinElevation())) * _scale.Z(); + float h = this->dataPtr->minElevation + + (h1 - ((h1 - h2) * dy) - this->dataPtr->minElevation) * _scale.Z(); // Invert pixel definition so 1=ground, 0=full height, // if the terrain size has a negative z component @@ -308,9 +354,9 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize, if (_size.Z() < 0) h *= -1; - // Convert to 0 if a NODATA value is found - if (_size.Z() >= 0 && h < 0) - h = 0; + // Convert to minElevation if a NODATA value is found + if (_size.Z() >= 0 && h < this->dataPtr->minElevation) + h = this->dataPtr->minElevation; // Store the height for future use if (!_flipY) @@ -326,14 +372,14 @@ int Dem::LoadData() { unsigned int destWidth; unsigned int destHeight; - unsigned int nXSize = this->dataPtr->dataSet->RasterXSize(); - unsigned int nYSize = this->dataPtr->dataSet->RasterYSize(); + unsigned int nXSize = this->dataPtr->dataSet->GetRasterXSize(); + unsigned int nYSize = this->dataPtr->dataSet->GetRasterYSize(); float ratio; std::vector buffer; if (nXSize == 0 || nYSize == 0) { - gzerr << "Illegal size loading a DEM file (" << nXSize << "," + ignerr << "Illegal size loading a DEM file (" << nXSize << "," << nYSize << ")\n"; return -1; } @@ -360,7 +406,7 @@ int Dem::LoadData() if (this->dataPtr->band->RasterIO(GF_Read, 0, 0, nXSize, nYSize, &buffer[0], destWidth, destHeight, GDT_Float32, 0, 0) != CE_None) { - gzerr << "Failure calling RasterIO while loading a DEM file\n"; + ignerr << "Failure calling RasterIO while loading a DEM file\n"; return -1; } @@ -378,4 +424,8 @@ int Dem::LoadData() return 0; } -#endif +////////////////////////////////////////////////// +std::string Dem::Filename() const +{ + return this->dataPtr->filename; +} diff --git a/graphics/src/Dem_TEST.cc b/geospatial/src/Dem_TEST.cc similarity index 51% rename from graphics/src/Dem_TEST.cc rename to geospatial/src/Dem_TEST.cc index bc39e7248..5a8fcde20 100644 --- a/graphics/src/Dem_TEST.cc +++ b/geospatial/src/Dem_TEST.cc @@ -16,6 +16,7 @@ */ #include +#include #include #include @@ -26,10 +27,8 @@ using namespace ignition; class DemTest : public common::testing::AutoLogFixture { }; -#ifdef HAVE_GDAL - ///////////////////////////////////////////////// -TEST_F(DemTest, MisingFile) +TEST_F(DemTest, MissingFile) { common::Dem dem; EXPECT_NE(dem.Load("/file/shouldn/never/exist.png"), 0); @@ -39,9 +38,7 @@ TEST_F(DemTest, MisingFile) TEST_F(DemTest, NotDem) { common::Dem dem; - std::string path; - - path = "file://media/materials/scripts/CMakeLists.txt"; + const auto path = common::testing::TestFile("CMakeLists.txt"); EXPECT_NE(dem.Load(path), 0); } @@ -49,9 +46,7 @@ TEST_F(DemTest, NotDem) TEST_F(DemTest, UnsupportedDem) { common::Dem dem; - std::string path; - - path = "file://media/materials/textures/wood.jpg"; + const auto path = common::testing::TestFile("data", "heightmap_bowl.png"); EXPECT_NE(dem.Load(path), 0); } @@ -86,30 +81,34 @@ TEST_F(DemTest, BasicAPI) const auto path = common::testing::TestFile("data", "dem_squared.tif"); EXPECT_EQ(dem.Load(path), 0); + // Check filename + EXPECT_EQ(path, dem.Filename()); + // Check the heights and widths - EXPECT_EQ(129, static_cast(dem.GetHeight())); - EXPECT_EQ(129, static_cast(dem.GetWidth())); - EXPECT_FLOAT_EQ(3984.4849, dem.GetWorldHeight()); - EXPECT_FLOAT_EQ(3139.7456, dem.GetWorldWidth()); - EXPECT_FLOAT_EQ(65.3583, dem.GetMinElevation()); - EXPECT_FLOAT_EQ(318.441, dem.GetMaxElevation()); - - // Check GetElevation() - unsigned int width = dem.GetWidth(); - unsigned int height = dem.GetHeight(); - EXPECT_FLOAT_EQ(215.82324, dem.GetElevation(0, 0)); - EXPECT_FLOAT_EQ(216.04961, dem.GetElevation(width - 1, 0)); - EXPECT_FLOAT_EQ(142.2274, dem.GetElevation(0, height - 1)); - EXPECT_FLOAT_EQ(209.14784, dem.GetElevation(width - 1, height - 1)); + EXPECT_EQ(129, static_cast(dem.Height())); + EXPECT_EQ(129, static_cast(dem.Width())); + EXPECT_FLOAT_EQ(3984.4849, dem.WorldHeight()); + EXPECT_FLOAT_EQ(3139.7456, dem.WorldWidth()); + EXPECT_FLOAT_EQ(65.3583, dem.MinElevation()); + EXPECT_FLOAT_EQ(318.441, dem.MaxElevation()); + + // Check Elevation() + unsigned int width = dem.Width(); + unsigned int height = dem.Height(); + EXPECT_FLOAT_EQ(215.82324, dem.Elevation(0, 0)); + EXPECT_FLOAT_EQ(216.04961, dem.Elevation(width - 1, 0)); + EXPECT_FLOAT_EQ(142.2274, dem.Elevation(0, height - 1)); + EXPECT_FLOAT_EQ(209.14784, dem.Elevation(width - 1, height - 1)); // Illegal coordinates - ASSERT_ANY_THROW(dem.GetElevation(0, height)); - ASSERT_ANY_THROW(dem.GetElevation(width, 0)); - ASSERT_ANY_THROW(dem.GetElevation(width, height)); + double inf = std::numeric_limits::infinity(); + EXPECT_DOUBLE_EQ(inf, dem.Elevation(0, height)); + EXPECT_DOUBLE_EQ(inf, dem.Elevation(width, 0)); + EXPECT_DOUBLE_EQ(inf, dem.Elevation(width, height)); - // Check GetGeoReferenceOrigin() + // Check GeoReferenceOrigin() ignition::math::Angle latitude, longitude; - dem.GetGeoReferenceOrigin(latitude, longitude); + EXPECT_TRUE(dem.GeoReferenceOrigin(latitude, longitude)); EXPECT_FLOAT_EQ(38.001667, latitude.Degree()); EXPECT_FLOAT_EQ(-122.22278, longitude.Degree()); } @@ -130,17 +129,17 @@ TEST_F(DemTest, FillHeightmap) std::vector elevations; subsampling = 2; - vertSize = (dem.GetWidth() * subsampling) - 1; - size.X(dem.GetWorldWidth()); - size.Y(dem.GetWorldHeight()); - size.Z(dem.GetMaxElevation() - dem.GetMinElevation()); + vertSize = (dem.Width() * subsampling) - 1; + size.X(dem.WorldWidth()); + size.Y(dem.WorldHeight()); + size.Z(dem.MaxElevation() - dem.MinElevation()); scale.X(size.X() / vertSize); scale.Y(size.Y() / vertSize); - if (ignition::math::equal(dem.GetMaxElevation(), 0.0f)) + if (ignition::math::equal(dem.MaxElevation(), 0.0f)) scale.Z(fabs(size.Z())); else - scale.Z(fabs(size.Z()) / dem.GetMaxElevation()); + scale.Z(fabs(size.Z()) / dem.MaxElevation()); flipY = false; dem.FillHeightMap(subsampling, vertSize, size, scale, flipY, elevations); @@ -149,11 +148,46 @@ TEST_F(DemTest, FillHeightmap) EXPECT_EQ(vertSize * vertSize, elevations.size()); // Check the elevation of some control points - EXPECT_FLOAT_EQ(119.58285, elevations.at(0)); - EXPECT_FLOAT_EQ(114.27753, elevations.at(elevations.size() - 1)); - EXPECT_FLOAT_EQ(148.07137, elevations.at(elevations.size() / 2)); + EXPECT_FLOAT_EQ(184.94113, elevations.at(0)); + EXPECT_FLOAT_EQ(179.63583, elevations.at(elevations.size() - 1)); + EXPECT_FLOAT_EQ(213.42966, elevations.at(elevations.size() / 2)); +} + +///////////////////////////////////////////////// +TEST_F(DemTest, UnfinishedDem) +{ + common::Dem dem; + auto path = common::testing::TestFile("data", "dem_unfinished.tif"); + EXPECT_EQ(dem.Load(path), 0); + + // Check that the min and max elevations are valid for an unfinished + // and unfilled dem. + EXPECT_EQ(33, static_cast(dem.Height())); + EXPECT_EQ(33, static_cast(dem.Width())); + EXPECT_FLOAT_EQ(111287.59, dem.WorldHeight()); + EXPECT_FLOAT_EQ(88878.297, dem.WorldWidth()); + // gdal reports min elevation as -32768 but this is treated as a nodata + // by our dem class and ignored when computing the min elevation + EXPECT_FLOAT_EQ(-10, dem.MinElevation()); + EXPECT_FLOAT_EQ(1909, dem.MaxElevation()); + + // test another dem file with multiple nodata values + common::Dem demNoData; + + path = common::testing::TestFile("data", "dem_nodata.dem"); + EXPECT_EQ(demNoData.Load(path), 0); + + // Check that the min and max elevations are valid for a dem with multiple + // nodata values + EXPECT_EQ(65, static_cast(demNoData.Height())); + EXPECT_EQ(65, static_cast(demNoData.Width())); + EXPECT_FLOAT_EQ(7499.8281, demNoData.WorldHeight()); + EXPECT_FLOAT_EQ(14150.225, demNoData.WorldWidth()); + // gdal reports min elevation as -32767 but this is treated as a nodata + // by our dem class and ignored when computing the min elevation + EXPECT_FLOAT_EQ(682, demNoData.MinElevation()); + EXPECT_FLOAT_EQ(2932, demNoData.MaxElevation()); } -#endif ///////////////////////////////////////////////// int main(int argc, char **argv) diff --git a/graphics/src/ImageHeightmap.cc b/geospatial/src/ImageHeightmap.cc similarity index 100% rename from graphics/src/ImageHeightmap.cc rename to geospatial/src/ImageHeightmap.cc diff --git a/graphics/src/ImageHeightmap_TEST.cc b/geospatial/src/ImageHeightmap_TEST.cc similarity index 97% rename from graphics/src/ImageHeightmap_TEST.cc rename to geospatial/src/ImageHeightmap_TEST.cc index b40880879..2b93f845a 100644 --- a/graphics/src/ImageHeightmap_TEST.cc +++ b/geospatial/src/ImageHeightmap_TEST.cc @@ -28,7 +28,7 @@ class ImageHeightmapTest : public common::testing::AutoLogFixture { }; class DemTest : public common::testing::AutoLogFixture { }; ///////////////////////////////////////////////// -TEST_F(DemTest, MisingFile) +TEST_F(DemTest, MissingFile) { common::ImageHeightmap img; EXPECT_EQ(-1, img.Load("/file/shouldn/never/exist.png")); @@ -51,6 +51,9 @@ TEST_F(ImageHeightmapTest, BasicAPI) std::cout << "PATH[" << path << "]\n"; EXPECT_EQ(0, img.Load(path)); + // Check filename + EXPECT_EQ(path, img.Filename()); + // Check the heights and widths EXPECT_EQ(129, static_cast(img.Height())); EXPECT_EQ(129, static_cast(img.Width())); diff --git a/test/data/dem_landscape.tif b/test/data/dem_landscape.tif new file mode 100644 index 000000000..b86023728 Binary files /dev/null and b/test/data/dem_landscape.tif differ diff --git a/test/data/dem_nodata.dem b/test/data/dem_nodata.dem new file mode 100644 index 000000000..60b04bf4c Binary files /dev/null and b/test/data/dem_nodata.dem differ diff --git a/test/data/dem_portrait.tif b/test/data/dem_portrait.tif new file mode 100644 index 000000000..bc8034221 Binary files /dev/null and b/test/data/dem_portrait.tif differ diff --git a/test/data/dem_squared.tif b/test/data/dem_squared.tif new file mode 100644 index 000000000..dcb8dd082 Binary files /dev/null and b/test/data/dem_squared.tif differ diff --git a/test/data/dem_unfinished.tif b/test/data/dem_unfinished.tif new file mode 100644 index 000000000..3e7b0b65a Binary files /dev/null and b/test/data/dem_unfinished.tif differ