Skip to content

Commit

Permalink
PR feedback
Browse files Browse the repository at this point in the history
* Enforce linter and naming conventions
* Add missing getters for size limits and test them
* Enforce 80char column limit
* Move ConfigureLoadedSize to the implementation
* Document all functions
* Fix lambda name case

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Jul 31, 2024
1 parent 71bbd64 commit 0397e4b
Show file tree
Hide file tree
Showing 3 changed files with 76 additions and 35 deletions.
24 changes: 18 additions & 6 deletions geospatial/include/gz/common/geospatial/Dem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,30 @@ namespace gz
public: void SetSphericalCoordinates(
const math::SphericalCoordinates &_worldSphericalCoordinates);

/// \brief Gets the X size limit of the raster data to be loaded.
/// This is useful for large raster files.
/// \return The maximium size of the raster data to load in
/// the X direction
public: unsigned int RasterXSizeLimit();

/// \brief Sets the X size limit of the raster data to be loaded.
/// This is useful for large raster files.
/// \param[in] _xLimit The maximium size of the raster data to load in the X direction
public: void SetXSizeLimit(
/// \param[in] _xLimit The maximium size of the raster data to
/// load in the X direction
public: void SetRasterXSizeLimit(
const unsigned int &_xLimit);

/// \brief Gets the Y size limit of the raster data to be loaded.
/// This is useful for large raster files.
/// \return The maximium size of the raster data to load in the
/// X direction
public: unsigned int RasterYSizeLimit();

/// \brief Sets the Y size limit of the raster data to be loaded.
/// This is useful for large raster files.
/// \param[in] _yLimit The maximium size of the raster data to load in the X direction
public: void SetYSizeLimit(
/// \param[in] _yLimit The maximium size of the raster data to
/// load in the X direction
public: void SetRasterYSizeLimit(
const unsigned int &_yLimit);

/// \brief Load a DEM file.
Expand Down Expand Up @@ -146,8 +160,6 @@ namespace gz
gz::math::Angle &_latitude,
gz::math::Angle &_longitude) const;

private: [[nodiscard]] bool ConfigureLoadedSize();

/// \brief Get the terrain file as a data array. Due to the Ogre
/// constrains, the data might be stored in a bigger vector representing
/// a squared terrain with padding.
Expand Down
72 changes: 49 additions & 23 deletions geospatial/src/Dem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ using namespace common;
class gz::common::Dem::Implementation
{
/// \brief A set of associated raster bands.
public: GDALDataset* dataSet;
public: GDALDataset *dataSet;

/// \brief A pointer to the band.
public: GDALRasterBand *band;
Expand All @@ -53,11 +53,13 @@ class gz::common::Dem::Implementation
public: unsigned int maxYSize {std::numeric_limits<unsigned int>::max()};

/// \brief The desired length of data to load in the X direction.
/// Internally, the implementation may use a higher value for performance.
/// Internally, the implementation may use a
// higher value for performance.
public: unsigned int configuredXSize;

/// \brief The desired length of data to load in the Y direction.
/// Internally, the implementation may use a higher value for performance.
/// Internally, the implementation may use a
// higher value for performance.
public: unsigned int configuredYSize;

/// \brief Minimum elevation in meters.
Expand All @@ -83,6 +85,12 @@ class gz::common::Dem::Implementation
/// \brief Holds the spherical coordinates object from the world.
public: math::SphericalCoordinates sphericalCoordinates =
math::SphericalCoordinates();

/// \brief Once the user configures size limits, apply that
/// to the internal configured size, which is limited
/// based on the dataset size.
/// \return True if configured size was valid.
public: [[nodiscard]] bool ConfigureLoadedSize();
};

//////////////////////////////////////////////////
Expand All @@ -109,13 +117,25 @@ void Dem::SetSphericalCoordinates(
}

//////////////////////////////////////////////////
void Dem::SetXSizeLimit(const unsigned int &_xLimit)
unsigned int Dem::RasterXSizeLimit()
{
return this->dataPtr->maxXSize;
}

//////////////////////////////////////////////////
void Dem::SetRasterXSizeLimit(const unsigned int &_xLimit)
{
this->dataPtr->maxXSize = _xLimit;
}

//////////////////////////////////////////////////
void Dem::SetYSizeLimit(const unsigned int &_yLimit)
unsigned int Dem::RasterYSizeLimit()
{
return this->dataPtr->maxYSize;
}

//////////////////////////////////////////////////
void Dem::SetRasterYSizeLimit(const unsigned int &_yLimit)
{
this->dataPtr->maxYSize = _yLimit;
}
Expand All @@ -135,7 +155,7 @@ int Dem::Load(const std::string &_filename)
this->dataPtr->filename = fullName;

// Create a re-usable lambda for opening a dataset.
auto OpenInGdal = [this](const std::string& name) -> bool
auto openInGdal = [this](const std::string& name) -> bool
{
GDALDatasetH handle = GDALOpen(name.c_str(), GA_ReadOnly);
if (handle)
Expand All @@ -149,13 +169,14 @@ int Dem::Load(const std::string &_filename)
if (!exists(findFilePath(fullName)))
{
// https://github.com/gazebosim/gz-common/issues/596
// Attempt loading anyways to support /vsicurl, /vsizip, and other GDAL Virtual File Formats.
// Attempt loading anyways to support /vsicurl, /vsizip, and other
// GDAL Virtual File Formats.
// The "exists()" function does not handle GDAL's special formats.
if (!OpenInGdal(_filename)) {
if (!openInGdal(_filename)) {
gzerr << "Unable to read DEM file[" << _filename << "]." << std::endl;
return -1;
}
} else if(!OpenInGdal(fullName)){
} else if(!openInGdal(fullName)){
gzerr << "Unable to open DEM file[" << fullName
<< "]. Format not recognized as a supported dataset." << std::endl;
return -1;
Expand All @@ -173,8 +194,9 @@ int Dem::Load(const std::string &_filename)
// Set the pointer to the band
this->dataPtr->band = this->dataPtr->dataSet->GetRasterBand(1);

// Validate the raster size and apply the user-configured size limits on loaded data.
if(!ConfigureLoadedSize())
// Validate the raster size and apply the user-configured size limits
// on loaded data.
if(!this->dataPtr->ConfigureLoadedSize())
{
return -1;
}
Expand Down Expand Up @@ -495,20 +517,20 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize,
}
}

bool Dem::ConfigureLoadedSize()
bool gz::common::Dem::Implementation::ConfigureLoadedSize()
{
assert(this->dataPtr->dataSet != nullptr);
const unsigned int nRasterXSize = this->dataPtr->dataSet->GetRasterXSize();
const unsigned int nRasterYSize = this->dataPtr->dataSet->GetRasterYSize();
assert(this->dataSet != nullptr);
const unsigned int nRasterXSize = this->dataSet->GetRasterXSize();
const unsigned int nRasterYSize = this->dataSet->GetRasterYSize();
if (nRasterXSize == 0 || nRasterYSize == 0)
{
gzerr << "Illegal raster size loading a DEM file (" << nRasterXSize << ","
<< nRasterYSize << ")\n";
return false;
}

this->dataPtr->configuredXSize = std::min(nRasterXSize, this->dataPtr->maxXSize);
this->dataPtr->configuredYSize = std::min(nRasterYSize, this->dataPtr->maxYSize);
this->configuredXSize = std::min(nRasterXSize, this->maxXSize);
this->configuredYSize = std::min(nRasterYSize, this->maxYSize);
return true;
}

Expand Down Expand Up @@ -539,17 +561,20 @@ int Dem::LoadData()
float w = static_cast<float>(destHeight) / static_cast<float>(ratio);
destWidth = static_cast<unsigned int>(w);
}

// Read the whole raster data and convert it to a GDT_Float32 array.
// In this step the DEM is scaled to destWidth x destHeight.

std::vector<float> buffer;
// Convert to uint64_t for multiplication to avoid overflow.
// https://github.com/OSGeo/gdal/issues/9713
buffer.resize(static_cast<uint64_t>(destWidth) * static_cast<uint64_t>(destHeight));
//! @todo Do not assume users only want to load from the origin of the dataset.
buffer.resize(static_cast<uint64_t>(destWidth) * \
static_cast<uint64_t>(destHeight));
//! @todo Do not assume users only want to load
//! from the origin of the dataset.
// Instead, add a configuration to change where in the dataset to read from.
if (this->dataPtr->band->RasterIO(GF_Read, 0, 0, desiredXSize, desiredYSize, &buffer[0],
if (this->dataPtr->band->RasterIO(GF_Read, 0, 0,
desiredXSize, desiredYSize, &buffer[0],
destWidth, destHeight, GDT_Float32, 0, 0) != CE_None)
{
gzerr << "Failure calling RasterIO while loading a DEM file\n";
Expand All @@ -558,8 +583,9 @@ int Dem::LoadData()

// Copy and align 'buffer' into the target vector. The destination vector is
// initialized to max() and later converted to the minimum elevation, so all
// the points not contained in 'buffer' will be extra padding
this->dataPtr->demData.resize(static_cast<uint64_t>(this->Width()) * static_cast<uint64_t>(this->Height()),
// the points not contained in 'buffer' will be extra padding.
this->dataPtr->demData.resize(static_cast<uint64_t>(this->Width()) * \
static_cast<uint64_t>(this->Height()),
this->dataPtr->bufferVal);
for (unsigned int y = 0; y < destHeight; ++y)
{
Expand Down
15 changes: 9 additions & 6 deletions geospatial/src/Dem_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -287,19 +287,21 @@ TEST_F(DemTest, LargeVRTWithLimits)
{
// Load a large VRT DEM using GDAL but set limits on the size.
common::Dem dem;
dem.SetXSizeLimit(100);
dem.SetYSizeLimit(50);
dem.SetRasterXSizeLimit(100);
dem.SetRasterYSizeLimit(50);
auto const path = common::testing::TestFile("data", "ap_srtm1.vrt");
auto const res = dem.Load(path);
EXPECT_EQ(res, 0);
EXPECT_EQ(dem.RasterXSizeLimit(), 100);
EXPECT_EQ(dem.RasterYSizeLimit(), 50);
}

TEST_F(DemTest, LargeVRTWithVSIZIPAndLimits)
{
// Load a large vzizip VRT DEM using GDAL but set limits on the size.
common::Dem dem;
dem.SetXSizeLimit(100);
dem.SetYSizeLimit(50);
dem.SetRasterXSizeLimit(100);
dem.SetRasterYSizeLimit(50);
auto const path = common::testing::TestFile("data", "ap_srtm1.zip");
auto const res = dem.Load("/vsizip/" + path + "/ap_srtm1.vrt");
EXPECT_EQ(res, 0);
Expand All @@ -310,6 +312,7 @@ TEST_F(DemTest, LargeVRTWithoutLimitsThrows)
// Load a large VRT DEM without limits.
common::Dem dem;
auto const path = common::testing::TestFile("data", "ap_srtm1.vrt");
// We expect not to be able to allocate the data, so ensure we throw instead of segfault.
// We expect not to be able to allocate the data,
// so ensure we throw instead of segfault.
EXPECT_THROW(dem.Load(path), std::bad_alloc);
}
}

0 comments on commit 0397e4b

Please sign in to comment.