Skip to content

Commit

Permalink
Merge branch 'main' into add_common_testing
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll authored Apr 1, 2022
2 parents ed2c45a + f50d514 commit 0dc5711
Show file tree
Hide file tree
Showing 43 changed files with 176 additions and 319 deletions.
7 changes: 0 additions & 7 deletions av/src/AudioDecoder_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -152,10 +152,3 @@ TEST(AudioDecoder, IGN_UTILS_TEST_DISABLED_ON_WIN32(CheerFile))
dataBufferSize == 4987612u * 2);
}
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
7 changes: 0 additions & 7 deletions events/src/Event_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -298,10 +298,3 @@ TEST_F(EventTest, DestructionOrder)
conn.reset();
SUCCEED();
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
7 changes: 0 additions & 7 deletions events/src/MouseEvent_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -268,10 +268,3 @@ TEST_F(MouseEvent, Assignment)
EXPECT_EQ(otherEvent.Alt(), alt);
EXPECT_EQ(otherEvent.Control(), control);
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
12 changes: 6 additions & 6 deletions geospatial/include/ignition/common/geospatial/Dem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,11 +58,11 @@ namespace ignition

/// \brief Get the terrain's minimum elevation in meters.
/// \return The minimum elevation (meters).
public: float MinElevation() const;
public: float MinElevation() const override;

/// \brief Get the terrain's maximum elevation in meters.
/// \return The maximum elevation (meters).
public: float MaxElevation() const;
public: float MaxElevation() const override;

/// \brief Get the georeferenced coordinates (lat, long) of the terrain's
/// origin in WGS84.
Expand All @@ -79,7 +79,7 @@ namespace ignition
/// \return The terrain's height (points) satisfying the ogre constrains
/// (squared terrain with a height value that must be a power of two plus
/// one).
public: unsigned int Height() const;
public: unsigned int Height() const override;

/// \brief Get the terrain's width. Due to the Ogre constrains, this
/// value will be a power of two plus one. The value returned might be
Expand All @@ -88,7 +88,7 @@ namespace ignition
/// \return The terrain's width (points) satisfying the ogre constrains
/// (squared terrain with a width value that must be a power of two plus
/// one).
public: unsigned int Width() const;
public: unsigned int Width() const override;

/// \brief Get the real world width in meters.
/// \return Terrain's real world width in meters.
Expand All @@ -113,7 +113,7 @@ namespace ignition
const ignition::math::Vector3d &_size,
const ignition::math::Vector3d &_scale,
const bool _flipY,
std::vector<float> &_heights) const;
std::vector<float> &_heights) const override;

/// \brief Get the georeferenced coordinates (lat, long) of a terrain's
/// pixel in WGS84.
Expand All @@ -133,7 +133,7 @@ namespace ignition
private: int LoadData();

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

/// internal
/// \brief Pointer to the private data.
Expand Down
141 changes: 83 additions & 58 deletions geospatial/src/Dem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,9 @@ class ignition::common::Dem::Implementation
/// \brief Maximum elevation in meters.
public: double maxElevation;

/// \brief Value used to mark padding buffer data.
public: float bufferVal{std::numeric_limits<float>::max()};

/// \brief DEM data converted to be OGRE-compatible.
public: std::vector<float> demData;

Expand Down Expand Up @@ -184,21 +187,31 @@ int Dem::Load(const std::string &_filename)
// ignore them when computing the min elevation.
int validNoData = 0;
const double defaultNoDataValue = -9999;
double noDataValue = this->dataPtr->band->GetNoDataValue(&validNoData);
float 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)
for (const auto &d : this->dataPtr->demData)
{
if (d > noDataValue)
if (math::equal(d, this->dataPtr->bufferVal))
continue;

// All comparisons to NaN return false, so guard against NaN NoData
if (!std::isnan(noDataValue) && math::equal(d, noDataValue))
continue;

if (!std::isfinite(d))
{
if (d < min)
min = d;
if (d > max)
max = d;
continue;
}

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))
Expand All @@ -208,6 +221,13 @@ int Dem::Load(const std::string &_filename)

this->dataPtr->minElevation = min;
this->dataPtr->maxElevation = max;

// Buffer to min elevation
for (auto &d : this->dataPtr->demData)
{
if (math::equal(d, this->dataPtr->bufferVal))
d = this->dataPtr->minElevation;
}
return 0;
}

Expand Down Expand Up @@ -261,6 +281,11 @@ bool Dem::GeoReference(double _x, double _y,
// Transform the terrain's coordinate system to WGS84
const char *importString
= strdup(this->dataPtr->dataSet->GetProjectionRef());
if (importString == nullptr || importString[0] == '\0')
{
igndbg << "Projection coordinate system undefined." << std::endl;
return false;
}
sourceCs.importFromWkt(&importString);
targetCs.SetWellKnownGeogCS("WGS84");
cT = OGRCreateCoordinateTransformation(&sourceCs, &targetCs);
Expand All @@ -284,7 +309,7 @@ bool Dem::GeoReference(double _x, double _y,
}
else
{
ignerr << "Unable to obtain the georeferenced values for coordinates ("
igndbg << "Unable to obtain the georeferenced values for coordinates ("
<< _x << "," << _y << ")" << std::endl;
return false;
}
Expand Down Expand Up @@ -399,60 +424,60 @@ void Dem::FillHeightMap(int _subSampling, unsigned int _vertSize,
//////////////////////////////////////////////////
int Dem::LoadData()
{
unsigned int destWidth;
unsigned int destHeight;
unsigned int nXSize = this->dataPtr->dataSet->GetRasterXSize();
unsigned int nYSize = this->dataPtr->dataSet->GetRasterYSize();
float ratio;
std::vector<float> buffer;

if (nXSize == 0 || nYSize == 0)
{
ignerr << "Illegal size loading a DEM file (" << nXSize << ","
<< nYSize << ")\n";
return -1;
}
unsigned int nXSize = this->dataPtr->dataSet->GetRasterXSize();
unsigned int nYSize = this->dataPtr->dataSet->GetRasterYSize();
if (nXSize == 0 || nYSize == 0)
{
ignerr << "Illegal size loading a DEM file (" << nXSize << ","
<< nYSize << ")\n";
return -1;
}

// Scale the terrain keeping the same ratio between width and height
if (nXSize > nYSize)
{
ratio = static_cast<float>(nXSize) / static_cast<float>(nYSize);
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);
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);
}
// Scale the terrain keeping the same ratio between width and height
unsigned int destWidth;
unsigned int destHeight;
float ratio;
if (nXSize > nYSize)
{
ratio = static_cast<float>(nXSize) / static_cast<float>(nYSize);
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);
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
buffer.resize(destWidth * destHeight);
if (this->dataPtr->band->RasterIO(GF_Read, 0, 0, nXSize, nYSize, &buffer[0],
destWidth, destHeight, GDT_Float32, 0, 0) != CE_None)
{
ignerr << "Failure calling RasterIO while loading a DEM file\n";
return -1;
}
// 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;
buffer.resize(destWidth * destHeight);
if (this->dataPtr->band->RasterIO(GF_Read, 0, 0, nXSize, nYSize, &buffer[0],
destWidth, destHeight, GDT_Float32, 0, 0) != CE_None)
{
ignerr << "Failure calling RasterIO while loading a DEM file\n";
return -1;
}

// Copy and align 'buffer' into the target vector. The destination vector is
// initialized to 0, so all the points not contained in 'buffer' will be
// extra padding
this->dataPtr->demData.resize(this->Width() * this->Height());
for (unsigned int y = 0; y < destHeight; ++y)
{
std::copy(&buffer[destWidth * y], &buffer[destWidth * y] + destWidth,
this->dataPtr->demData.begin() + this->Width() * y);
}
buffer.clear();
// 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(),
this->dataPtr->bufferVal);
for (unsigned int y = 0; y < destHeight; ++y)
{
std::copy(&buffer[destWidth * y], &buffer[destWidth * y] + destWidth,
this->dataPtr->demData.begin() + this->Width() * y);
}
buffer.clear();

return 0;
return 0;
}

//////////////////////////////////////////////////
Expand Down
48 changes: 36 additions & 12 deletions geospatial/src/Dem_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,13 @@ TEST_F(DemTest, NonSquaredDemPortrait)
common::Dem dem;
const auto path = common::testing::TestFile("data", "dem_portrait.tif");
EXPECT_EQ(dem.Load(path), 0);
EXPECT_DOUBLE_EQ(dem.Width(), dem.Height());
EXPECT_DOUBLE_EQ(257, dem.Height());
EXPECT_DOUBLE_EQ(257, dem.Width());
EXPECT_DOUBLE_EQ(111565.57640012962, dem.WorldHeight());
EXPECT_DOUBLE_EQ(87912.450080798269, dem.WorldWidth());
EXPECT_DOUBLE_EQ(-6.2633352279663086, dem.MinElevation());
EXPECT_DOUBLE_EQ(920.762939453125, dem.MaxElevation());
}

/////////////////////////////////////////////////
Expand All @@ -64,6 +71,13 @@ TEST_F(DemTest, NonSquaredDemLandscape)
common::Dem dem;
const auto path = common::testing::TestFile("data", "dem_landscape.tif");
EXPECT_EQ(dem.Load(path), 0);
EXPECT_DOUBLE_EQ(dem.Width(), dem.Height());
EXPECT_DOUBLE_EQ(257, dem.Height());
EXPECT_DOUBLE_EQ(257, dem.Width());
EXPECT_DOUBLE_EQ(111565.57640012962, dem.WorldHeight());
EXPECT_DOUBLE_EQ(87912.450080798269, dem.WorldWidth());
EXPECT_DOUBLE_EQ(-4.7324686050415039, dem.MinElevation());
EXPECT_DOUBLE_EQ(921.4481201171875, dem.MaxElevation());
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -166,9 +180,7 @@ TEST_F(DemTest, UnfinishedDem)
EXPECT_EQ(33, static_cast<int>(dem.Width()));
EXPECT_FLOAT_EQ(111287.59f, dem.WorldHeight());
EXPECT_FLOAT_EQ(88878.297f, 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.0f, dem.MinElevation());
EXPECT_FLOAT_EQ(-32768.0f, dem.MinElevation());
EXPECT_FLOAT_EQ(1909.0f, dem.MaxElevation());

// test another dem file with multiple nodata values
Expand All @@ -186,12 +198,31 @@ TEST_F(DemTest, UnfinishedDem)
EXPECT_NEAR(7499.8281, demNoData.WorldHeight(), 0.1);
EXPECT_NEAR(14150.225, demNoData.WorldWidth(), 0.1);

// gdal reports min elevation as -32767 but this is treated as a nodata
// by our dem class and ignored when computing the min elevation
// -32767 is the nodata value, so it's ignored when computing the min
// elevation
EXPECT_FLOAT_EQ(682.0f, demNoData.MinElevation());
EXPECT_FLOAT_EQ(2932.0f, demNoData.MaxElevation());
}

/////////////////////////////////////////////////
TEST_F(DemTest, NaNNoData)
{
common::Dem dem;
auto path = common::testing::TestFile("data", "dem_nodata_nan.nc");
EXPECT_EQ(dem.Load(path), 0);

// Check that the min and max elevations are valid for a DEM with NaN
// nodata values
EXPECT_EQ(129, static_cast<int>(dem.Height()));
EXPECT_EQ(129, static_cast<int>(dem.Width()));

EXPECT_NEAR(7464.7589424555326, dem.WorldHeight(), 0.1);
EXPECT_NEAR(14244.280980717675, dem.WorldWidth(), 0.1);

EXPECT_FLOAT_EQ(682.0f, dem.MinElevation());
EXPECT_FLOAT_EQ(2932.0f, dem.MaxElevation());
}

/////////////////////////////////////////////////
TEST_F(DemTest, NonEarthDem)
{
Expand All @@ -213,10 +244,3 @@ TEST_F(DemTest, NonEarthDem)
ignition::math::Angle latitude, longitude;
EXPECT_FALSE(dem.GeoReferenceOrigin(latitude, longitude));
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
7 changes: 0 additions & 7 deletions geospatial/src/ImageHeightmap_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -99,10 +99,3 @@ TEST_F(ImageHeightmapTest, FillHeightmap)
EXPECT_NEAR(10.0, elevations.at(elevations.size() - 1), ELEVATION_TOL);
EXPECT_NEAR(5.0, elevations.at(elevations.size() / 2), ELEVATION_TOL);
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
7 changes: 0 additions & 7 deletions graphics/src/Animation_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -272,10 +272,3 @@ TEST_F(AnimationTest, TrajectoryInfo)
EXPECT_DOUBLE_EQ(0.0, trajInfo4.DistanceSoFar(2000ms));
EXPECT_DOUBLE_EQ(0.0, trajInfo4.DistanceSoFar(3000ms));
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
7 changes: 0 additions & 7 deletions graphics/src/ColladaExporter_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -443,10 +443,3 @@ TEST_F(ColladaExporter, ExportLights)
}
EXPECT_EQ(node_with_light_count, 3);
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
Loading

0 comments on commit 0dc5711

Please sign in to comment.