Skip to content

Commit

Permalink
DEM: Add support for GDAL vsicurl, vsizip support and avoid segfaults…
Browse files Browse the repository at this point in the history
… with huge VRT datasets (#597)

1. Adds initial support to load super large DEM datasets by exposing an API to limit the size of the loaded DEM.
1. Adds an alternative way of loading datafiles that make use of features like `vsizip` and `vsicurl` that aren't true filepaths.
1. Adds a compiler warning for if you use new versions of GDAL, which will lose precision in the current implementation, and potentially misrepresent NoData values.
   * This could be taken out, but could be an issue instead. A printed warning could be ok.
1. Add a few asserts for safety to catch coding errors earlier
1. The user-configurable size limits can be used to prevent segmentation faults by loading too big of a raster dataset
1. FIxed overflow and segfault in RasterIO for massive DEM's and overflow risk in vector resize operations

---------

Signed-off-by: Ryan Friedman <[email protected]>
Signed-off-by: Ryan <[email protected]>
Signed-off-by: Addisu Z. Taddese <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Addisu Z. Taddese <[email protected]>
Co-authored-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
4 people authored Aug 6, 2024
1 parent ad1d5ad commit 85b12c6
Show file tree
Hide file tree
Showing 6 changed files with 192,170 additions and 32 deletions.
28 changes: 27 additions & 1 deletion geospatial/include/gz/common/geospatial/Dem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,38 @@ namespace gz
public: virtual ~Dem();

/// \brief Sets the spherical coordinates reference object.
/// \param[in] _worldSphericalCoordinates The spherical coordiantes
/// \param[in] _worldSphericalCoordinates The spherical coordinates
/// object contained in the world. This is used to compute accurate
/// sizes of the DEM object.
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 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 SetRasterYSizeLimit(
const unsigned int &_yLimit);

/// \brief Load a DEM file.
/// \param[in] _filename the path to the terrain file.
/// \return 0 when the operation succeeds to open a file.
Expand Down
152 changes: 121 additions & 31 deletions geospatial/src/Dem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,24 @@ class gz::common::Dem::Implementation
/// \brief Terrain's side (after the padding).
public: unsigned int side;

/// \brief The maximum length of data to load in the X direction.
/// By default, load the entire raster.
public: unsigned int maxXSize {std::numeric_limits<unsigned int>::max()};

/// \brief The maximum length of data to load in the Y direction.
/// By default, load the entire raster.
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.
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.
public: unsigned int configuredYSize;

/// \brief Minimum elevation in meters.
public: double minElevation;

Expand All @@ -67,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 @@ -81,9 +105,8 @@ Dem::Dem()
Dem::~Dem()
{
this->dataPtr->demData.clear();

if (this->dataPtr->dataSet)
GDALClose(reinterpret_cast<GDALDataset *>(this->dataPtr->dataSet));
GDALClose(GDALDataset::ToHandle(this->dataPtr->dataSet));
}

//////////////////////////////////////////////////
Expand All @@ -93,12 +116,33 @@ void Dem::SetSphericalCoordinates(
this->dataPtr->sphericalCoordinates = _worldSphericalCoordinates;
}

//////////////////////////////////////////////////
unsigned int Dem::RasterXSizeLimit()
{
return this->dataPtr->maxXSize;
}

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

//////////////////////////////////////////////////
unsigned int Dem::RasterYSizeLimit()
{
return this->dataPtr->maxYSize;
}

//////////////////////////////////////////////////
void Dem::SetRasterYSizeLimit(const unsigned int &_yLimit)
{
this->dataPtr->maxYSize = _yLimit;
}

//////////////////////////////////////////////////
int Dem::Load(const std::string &_filename)
{
unsigned int width;
unsigned int height;
int xSize, ySize;
double upLeftX, upLeftY, upRightX, upRightY, lowLeftX, lowLeftY;
gz::math::Angle upLeftLat, upLeftLong, upRightLat, upRightLong;
gz::math::Angle lowLeftLat, lowLeftLong;
Expand All @@ -110,21 +154,34 @@ int Dem::Load(const std::string &_filename)

this->dataPtr->filename = fullName;

if (!exists(findFilePath(fullName)))
// Create a re-usable lambda for opening a dataset.
auto openInGdal = [this](const std::string& name) -> bool
{
gzerr << "Unable to find DEM file[" << _filename << "]." << std::endl;
return -1;
}
GDALDatasetH handle = GDALOpen(name.c_str(), GA_ReadOnly);
if (handle)
{
this->dataPtr->dataSet = GDALDataset::FromHandle(handle);
}

this->dataPtr->dataSet = reinterpret_cast<GDALDataset *>(GDALOpen(
fullName.c_str(), GA_ReadOnly));
return this->dataPtr->dataSet != nullptr;
};

if (this->dataPtr->dataSet == nullptr)
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.
// The "exists()" function does not handle GDAL's special formats.
if (!openInGdal(_filename)) {
gzerr << "Unable to read DEM file[" << _filename << "]." << std::endl;
return -1;
}
} else if(!openInGdal(fullName)){
gzerr << "Unable to open DEM file[" << fullName
<< "]. Format not recognized as a supported dataset." << std::endl;
return -1;
}
assert(this->dataPtr->dataSet != nullptr);

int nBands = this->dataPtr->dataSet->GetRasterCount();
if (nBands != 1)
Expand All @@ -137,9 +194,16 @@ 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(!this->dataPtr->ConfigureLoadedSize())
{
return -1;
}

// Raster width and height
xSize = this->dataPtr->dataSet->GetRasterXSize();
ySize = this->dataPtr->dataSet->GetRasterYSize();
const int xSize = this->dataPtr->configuredXSize;
const int ySize = this->dataPtr->configuredYSize;

// Corner coordinates
upLeftX = 0.0;
Expand Down Expand Up @@ -173,16 +237,20 @@ int Dem::Load(const std::string &_filename)
}

// Set the terrain's side (the terrain will be squared after the padding)

unsigned int height;
if (gz::math::isPowerOfTwo(ySize - 1))
height = ySize;
else
height = gz::math::roundUpPowerOfTwo(ySize) + 1;

unsigned int width;
if (gz::math::isPowerOfTwo(xSize - 1))
width = xSize;
else
width = gz::math::roundUpPowerOfTwo(xSize) + 1;

//! @todo use by limits.
this->dataPtr->side = std::max(width, height);

// Preload the DEM's data
Expand Down Expand Up @@ -226,7 +294,7 @@ int Dem::Load(const std::string &_filename)
if (gz::math::equal(min, gz::math::MAX_D) ||
gz::math::equal(max, -gz::math::MAX_D))
{
gzwarn << "DEM is composed of 'nodata' values!" << std::endl;
gzwarn << "The DEM contains 'nodata' values!" << std::endl;
}

this->dataPtr->minElevation = min;
Expand Down Expand Up @@ -281,6 +349,7 @@ bool Dem::GeoReference(double _x, double _y,
}

double geoTransf[6];
assert(this->dataPtr->dataSet != nullptr);
if (this->dataPtr->dataSet->GetGeoTransform(geoTransf) == CE_None)
{
OGRCoordinateTransformation *cT = nullptr;
Expand Down Expand Up @@ -448,44 +517,64 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize,
}
}

//////////////////////////////////////////////////
int Dem::LoadData()
bool gz::common::Dem::Implementation::ConfigureLoadedSize()
{
unsigned int nXSize = this->dataPtr->dataSet->GetRasterXSize();
unsigned int nYSize = this->dataPtr->dataSet->GetRasterYSize();
if (nXSize == 0 || nYSize == 0)
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 size loading a DEM file (" << nXSize << ","
<< nYSize << ")\n";
return -1;
gzerr << "Illegal raster size loading a DEM file (" << nRasterXSize << ","
<< nRasterYSize << ")\n";
return false;
}

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

//////////////////////////////////////////////////
int Dem::LoadData()
{
// Capture a local for re-use.
const auto desiredXSize = this->dataPtr->configuredXSize;
const auto desiredYSize = this->dataPtr->configuredYSize;

// Scale the terrain keeping the same ratio between width and height
unsigned int destWidth;
unsigned int destHeight;
float ratio;
if (nXSize > nYSize)
if (desiredXSize > desiredYSize)
{
ratio = static_cast<float>(nXSize) / static_cast<float>(nYSize);
ratio = static_cast<float>(desiredXSize) / static_cast<float>(desiredYSize);
destWidth = this->dataPtr->side;
// The decimal part is discarted for interpret the result as pixels
float h = static_cast<float>(destWidth) / static_cast<float>(ratio);
destHeight = static_cast<unsigned int>(h);
}
else
{
ratio = static_cast<float>(nYSize) / static_cast<float>(nXSize);
ratio = static_cast<float>(desiredYSize) / static_cast<float>(desiredXSize);
destHeight = this->dataPtr->side;
// The decimal part is discarted for interpret the result as pixels
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
// In this step the DEM is scaled to destWidth x destHeight.

std::vector<float> buffer;
buffer.resize(destWidth * destHeight);
if (this->dataPtr->band->RasterIO(GF_Read, 0, 0, nXSize, nYSize, &buffer[0],
// 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.
// 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],
destWidth, destHeight, GDT_Float32, 0, 0) != CE_None)
{
gzerr << "Failure calling RasterIO while loading a DEM file\n";
Expand All @@ -494,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(this->Width() * 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
35 changes: 35 additions & 0 deletions geospatial/src/Dem_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -282,3 +282,38 @@ TEST_F(DemTest, LunarDemLoad)
EXPECT_NEAR(dem.WorldWidth(), 80.0417, 1e-2);
EXPECT_NEAR(dem.WorldHeight(), 80.0417, 1e-2);
}

TEST_F(DemTest, LargeVRTWithLimits)
{
// Load a large VRT DEM using GDAL but set limits on the size.
common::Dem dem;
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.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);
}

TEST_F(DemTest, LargeVRTWithoutLimitsThrows)
{
GTEST_SKIP() << "Skipping this test because it's not platform-portable";
// 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.
EXPECT_THROW(dem.Load(path), std::bad_alloc);
}
4 changes: 4 additions & 0 deletions graphics/src/AssimpLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -513,6 +513,10 @@ MaterialPtr AssimpLoader::Implementation::CreateMaterial(
pbr.SetRoughness(value);
}
#endif
std::cout << "Diffuse: " << mat->Diffuse() << std::endl;
std::cout << "Specular: " << mat->Specular() << std::endl;
std::cout << "Roughness: " << pbr.Roughness() << std::endl;
std::cout << "Metalness: " << pbr.Metalness() << std::endl;
mat->SetPbrMaterial(pbr);
return mat;
}
Expand Down
Loading

0 comments on commit 85b12c6

Please sign in to comment.