Skip to content

Commit

Permalink
Adds bounds retrieval for TimeVarying grid class. (#508)
Browse files Browse the repository at this point in the history
* Adds bounds retrieval for TimeVarying grid class.

This is required for visualization purposes.

Signed-off-by: Arjo Chakravarty <[email protected]>
  • Loading branch information
arjo129 authored Oct 11, 2022
1 parent 39e48c1 commit 1bcf7d1
Show file tree
Hide file tree
Showing 6 changed files with 131 additions and 2 deletions.
12 changes: 12 additions & 0 deletions include/gz/math/TimeVaryingVolumetricGrid.hh
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,10 @@ class TimeVaryingVolumetricGrid
/// \param[in] _pos - The position of the point we want to query
public: std::optional<V> LookUp(const S &_session, const Vector3<P> &_pos)
const;

/// \brief Get the bounds of this grid field at given time.
/// \return A pair of vectors. All zeros if session is invalid.
public: std::pair<Vector3<V>, Vector3<V>> Bounds(const S &_session) const;
};

/// \brief Specialization of TimeVaryingVolumetricGrid which loads the whole of
Expand Down Expand Up @@ -93,6 +97,14 @@ class TimeVaryingVolumetricGrid<T, V, InMemorySession<T, P>, P>
return result;
}

/// \brief Get the bounds of this grid field at given time.
/// \return A pair of vectors. All zeros if session is invalid.
public: std::pair<Vector3<V>, Vector3<V>> Bounds(
const InMemorySession<T, P> &_session) const
{
return indices.Bounds(_session);
}

/// Buffer for values being stored
private: std::vector<V> values;

Expand Down
20 changes: 20 additions & 0 deletions include/gz/math/TimeVaryingVolumetricGridLookupField.hh
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,10 @@ namespace gz
const std::vector<X> &_values2,
const X _default = X(0)
) const;

/// \brief Get the bounds of this grid field.
/// \return A pair of vectors.
public: std::pair<Vector3<V>, Vector3<V>> Bounds(const S &_session);
};

/// \brief An in-memory session. Loads the whole dataset in memory and
Expand Down Expand Up @@ -285,6 +289,22 @@ namespace gz
// Return nullopt if we are out of range
return std::nullopt;
}

/// \brief Get the bounds of this grid field.
/// \return A pair of vectors. All zeros if session is invalid.
public: std::pair<Vector3<V>, Vector3<V>> Bounds(
const InMemorySession<T, V> &_session) const
{
if (_session.iter == this->gridFields.end())
{
// Out of bounds
return std::pair<Vector3<T>, Vector3<T>>(
Vector3<T>{0, 0, 0}, Vector3<T>{0, 0, 0}
);
}
return _session.iter->second.Bounds();
}

private: std::map<T, VolumetricGridLookupField<V>> gridFields;
};
}
Expand Down
20 changes: 19 additions & 1 deletion include/gz/math/VolumetricGridLookupField.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,9 @@
#ifndef GZ_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_
#define GZ_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_

#include <vector>
#include <optional>
#include <utility>
#include <vector>

#include <gz/math/Vector3.hh>
#include <gz/math/detail/InterpolationPoint.hh>
Expand Down Expand Up @@ -262,6 +263,23 @@ namespace gz
}
}

/// \brief Get the bounds of this grid field.
/// \return A pair of vectors.
public: std::pair<Vector3<T>, Vector3<T>> Bounds() const
{
return std::pair<Vector3<T>, Vector3<T>>(
Vector3<T>{
x_indices_by_lat.MinKey(),
y_indices_by_lon.MinKey(),
z_indices_by_depth.MinKey()
},
Vector3<T>{
x_indices_by_lat.MaxKey(),
y_indices_by_lon.MaxKey(),
z_indices_by_depth.MaxKey()
});
}

};
}
}
Expand Down
24 changes: 24 additions & 0 deletions include/gz/math/detail/AxisIndex.hh
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,30 @@ namespace gz
/// \brief Number of indices
private: int numIndices{0};

/// \brief Minimum key
/// \return the minimum key or zero if the axis is empty.
public: T MinKey() const
{
auto key = axisIndex.begin();
if (key == axisIndex.end())
{
return T(0);
}
return key->first;
}

/// \brief Maximum key
/// \return the maximum key or zero if the axis is empty.
public: T MaxKey() const
{
auto key = axisIndex.rbegin();
if (key == axisIndex.rend())
{
return T(0);
}
return key->first;
}

/// \brief Register the existance of a measurement at _value.
/// \param[in] _value The position of the measurement.
public: void AddIndexIfNotFound(T _value)
Expand Down
52 changes: 52 additions & 0 deletions src/TimeVaryingVolumetricGrid_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -63,3 +63,55 @@ TEST(TimeVaryingVolumetricGridTest, TestConstruction)
val = grid.LookUp(new_sess.value(), Vector3d{2.5, 2.5, 2.5});
ASSERT_FALSE(val.has_value());
}

/////////////////////////////////////////////////
TEST(TimeVaryingVolumetricGridTest, TestBounds)
{
InMemoryTimeVaryingVolumetricGridFactory<double, double> gridFactory;

for (double t = 0; t <= 1; t+=0.2)
{
for (double x = -1; x <= 1; x+=0.5)
{
for (double y = -1; y <= 1; y+=0.5)
{
for (double z = -1; z <= 1; z+=0.5)
{
gridFactory.AddPoint(t, Vector3d{x, y, z}, t);
}
}
}
}

auto grid = gridFactory.Build();
auto session = grid.CreateSession();

auto [min, max] = grid.Bounds(session);

ASSERT_NEAR(min.X(), -1.0, 1e-6);
ASSERT_NEAR(min.Y(), -1.0, 1e-6);
ASSERT_NEAR(min.Z(), -1.0, 1e-6);

ASSERT_NEAR(max.X(), 1.0, 1e-6);
ASSERT_NEAR(max.Y(), 1.0, 1e-6);
ASSERT_NEAR(max.Z(), 1.0, 1e-6);
}

/////////////////////////////////////////////////
TEST(TimeVaryingVolumetricGridTest, TestEmptyGrid)
{
InMemoryTimeVaryingVolumetricGridFactory<double, double> gridFactory;

auto grid = gridFactory.Build();
auto session = grid.CreateSession();

auto [min, max] = grid.Bounds(session);

ASSERT_NEAR(min.X(), 0, 1e-6);
ASSERT_NEAR(min.Y(), 0, 1e-6);
ASSERT_NEAR(min.Z(), 0, 1e-6);

ASSERT_NEAR(max.X(), 0, 1e-6);
ASSERT_NEAR(max.Y(), 0, 1e-6);
ASSERT_NEAR(max.Z(), 0, 1e-6);
}
5 changes: 4 additions & 1 deletion src/VolumetricGridLookupField_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -182,12 +182,15 @@ TEST(VolumetricGridLookupField, CheckTrilinearInterpolationBoxEightPoints)
}
}


TEST(VolumetricGridLookupField, AxisIndexTest)
{
AxisIndex<double> axis;
EXPECT_EQ(axis.MinKey(), 0.0);
EXPECT_EQ(axis.MaxKey(), 0.0);
axis.AddIndexIfNotFound(300);
axis.AddIndexIfNotFound(300);
EXPECT_EQ(axis.MinKey(), 300.0);
EXPECT_EQ(axis.MaxKey(), 300.0);
EXPECT_EQ(axis.GetNumUniqueIndices(), 1UL);
EXPECT_EQ(axis.GetIndex(300).value(), 0UL);
EXPECT_EQ(axis.GetIndex(200).has_value(), false);
Expand Down

0 comments on commit 1bcf7d1

Please sign in to comment.