Skip to content

Commit

Permalink
Add Region3 class (#390)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Mar 21, 2022
1 parent 5f3c3ed commit 289dbc3
Show file tree
Hide file tree
Showing 4 changed files with 447 additions and 0 deletions.
3 changes: 3 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@ target_link_libraries(quaternion_to_euler ignition-math${IGN_MATH_VER}::ignition
add_executable(rand_example rand_example.cc)
target_link_libraries(rand_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

add_executable(region3_example region3_example.cc)
target_link_libraries(region3_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

add_executable(temperature_example temperature_example.cc)
target_link_libraries(temperature_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

Expand Down
61 changes: 61 additions & 0 deletions examples/region3_example.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
//! [complete]
#include <iostream>
#include <ignition/math/Region3.hh>
#include <ignition/math/Vector3.hh>

int main(int argc, char **argv)
{
std::cout << std::boolalpha;

const ignition::math::Region3d defaultRegion;
// A default constructed region should be empty.
std::cout << "The " << defaultRegion << " region is empty: "
<< defaultRegion.Empty() << std::endl;

const ignition::math::Region3d openRegion =
ignition::math::Region3d::Open(-1., -1., -1., 1., 1., 1.);
// An open region should exclude points on its boundary.
std::cout << "The " << openRegion << " region contains the "
<< ignition::math::Vector3d::UnitX << " point: "
<< openRegion.Contains(ignition::math::Vector3d::UnitX)
<< std::endl;

const ignition::math::Region3d closedRegion =
ignition::math::Region3d::Closed(0., 0., 0., 1., 1., 1.);

// A closed region should include points on its boundary.
std::cout << "The " << closedRegion << " region contains the "
<< ignition::math::Vector3d::UnitX << " point: "
<< closedRegion.Contains(ignition::math::Vector3d::UnitX)
<< std::endl;

// Closed and open regions may intersect.
std::cout << "Regions " << closedRegion << " and " << openRegion
<< " intersect: " << closedRegion.Intersects(openRegion)
<< std::endl;

// The unbounded region should include all non-empty regions.
std::cout << "The " << ignition::math::Region3d::Unbounded
<< " region contains all previous non-empty intervals: "
<< (ignition::math::Region3d::Unbounded.Contains(openRegion) ||
ignition::math::Region3d::Unbounded.Contains(closedRegion))
<< std::endl;

}
//! [complete]
208 changes: 208 additions & 0 deletions include/ignition/math/Region3.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,208 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_MATH_REGION3_HH_
#define IGNITION_MATH_REGION3_HH_

#include <cmath>
#include <limits>
#include <ostream>
#include <utility>

#include <ignition/math/Interval.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/config.hh>

namespace ignition
{
namespace math
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
/// \class Region3 Region3.hh ignition/math/Region3.hh
/// \brief The Region3 class represents the cartesian product
/// of intervals Ix ✕ Iy ✕ Iz, one per axis, yielding an
/// axis-aligned region of R^3 space. It can be thought of as
/// an intersection of halfspaces. Regions may be open or
/// closed in their boundaries, if any.
///
/// Note that the Region3 class is essentially a set R ⊆ R^3.
/// For 3D solid box semantics, use the `AxisAlignedBox` class
/// instead.
///
/// ## Example
///
/// \snippet examples/region3_example.cc complete
template <typename T>
class Region3
{
/// \brief An unbounded region (-∞, ∞) ✕ (-∞, ∞) ✕ (-∞, ∞)
public: static const Region3<T> &Unbounded;

/// \brief Constructor
public: Region3() = default;

/// \brief Constructor
/// \param[in] _ix x-axis interval
/// \param[in] _iy y-axis interval
/// \param[in] _iz z-axis interval
public: Region3(Interval<T> _ix, Interval<T> _iy, Interval<T> _iz)
: ix(std::move(_ix)), iy(std::move(_iy)), iz(std::move(_iz))
{
}

/// \brief Make an open region
/// \param[in] _xLeft leftmost x-axis interval value
/// \param[in] _xRight righmost x-axis interval value
/// \param[in] _yLeft leftmost y-axis interval value
/// \param[in] _yRight righmost y-axis interval value
/// \param[in] _zLeft leftmost z-axis interval value
/// \param[in] _zRight righmost z-axis interval value
/// \return the (`_xLeft`, `_xRight`) ✕ (`_yLeft`, `_yRight`)
/// ✕ (`_zLeft`, `_zRight`) open region
public: static Region3<T> Open(
T _xLeft, T _yLeft, T _zLeft,
T _xRight, T _yRight, T _zRight)
{
return Region3<T>(Interval<T>::Open(_xLeft, _xRight),
Interval<T>::Open(_yLeft, _yRight),
Interval<T>::Open(_zLeft, _zRight));
}

/// \brief Make a closed region
/// \param[in] _xLeft leftmost x-axis interval value
/// \param[in] _xRight righmost x-axis interval value
/// \param[in] _yLeft leftmost y-axis interval value
/// \param[in] _yRight righmost y-axis interval value
/// \param[in] _zLeft leftmost z-axis interval value
/// \param[in] _zRight righmost z-axis interval value
/// \return the [`_xLeft`, `_xRight`] ✕ [`_yLeft`, `_yRight`]
/// ✕ [`_zLeft`, `_zRight`] closed region
public: static Region3<T> Closed(
T _xLeft, T _yLeft, T _zLeft,
T _xRight, T _yRight, T _zRight)
{
return Region3<T>(Interval<T>::Closed(_xLeft, _xRight),
Interval<T>::Closed(_yLeft, _yRight),
Interval<T>::Closed(_zLeft, _zRight));
}

/// \brief Get the x-axis interval for the region
/// \return the x-axis interval
public: const Interval<T> &Ix() const { return this->ix; }

/// \brief Get the y-axis interval for the region
/// \return the y-axis interval
public: const Interval<T> &Iy() const { return this->iy; }

/// \brief Get the z-axis interval for the region
/// \return the z-axis interval
public: const Interval<T> &Iz() const { return this->iz; }

/// \brief Check if the region is empty
/// A region is empty if any of the intervals
/// it is defined with (i.e. Ix, Iy, Iz) are.
/// \return true if it is empty, false otherwise
public: bool Empty() const
{
return this->ix.Empty() || this->iy.Empty() || this->iz.Empty();
}

/// \brief Check if the region contains `_point`
/// \param[in] _point point to check for membership
/// \return true if it is contained, false otherwise
public: bool Contains(const Vector3<T> &_point) const
{
return (this->ix.Contains(_point.X()) &&
this->iy.Contains(_point.Y()) &&
this->iz.Contains(_point.Z()));
}

/// \brief Check if the region contains `_other` region
/// \param[in] _other region to check for membership
/// \return true if it is contained, false otherwise
public: bool Contains(const Region3<T> &_other) const
{
return (this->ix.Contains(_other.ix) &&
this->iy.Contains(_other.iy) &&
this->iz.Contains(_other.iz));
}

/// \brief Check if the region intersects `_other` region
/// \param[in] _other region to check for intersection
/// \return true if it is contained, false otherwise
public: bool Intersects(const Region3<T>& _other) const
{
return (this->ix.Intersects(_other.ix) &&
this->iy.Intersects(_other.iy) &&
this->iz.Intersects(_other.iz));
}

/// \brief Equality test operator
/// \param _other region to check for equality
/// \return true if regions are equal, false otherwise
public: bool operator==(const Region3<T> &_other) const
{
return this->Contains(_other) && _other.Contains(*this);
}

/// \brief Inequality test operator
/// \param _other region to check for inequality
/// \return true if regions are unequal, false otherwise
public: bool operator!=(const Region3<T> &_other) const
{
return !this->Contains(_other) || !_other.Contains(*this);
}

/// \brief Stream insertion operator
/// \param _out output stream
/// \param _r Region3 to output
/// \return the stream
public: friend std::ostream &operator<<(
std::ostream &_out, const ignition::math::Region3<T> &_r)
{
return _out <<_r.ix << " x " << _r.iy << " x " << _r.iz;
}

/// \brief The x-axis interval
private: Interval<T> ix;
/// \brief The y-axis interval
private: Interval<T> iy;
/// \brief The z-axis interval
private: Interval<T> iz;
};

namespace detail {
template<typename T>
const Region3<T> gUnboundedRegion3(
Interval<T>::Open(-std::numeric_limits<T>::infinity(),
std::numeric_limits<T>::infinity()),
Interval<T>::Open(-std::numeric_limits<T>::infinity(),
std::numeric_limits<T>::infinity()),
Interval<T>::Open(-std::numeric_limits<T>::infinity(),
std::numeric_limits<T>::infinity()));
}
template<typename T>
const Region3<T> &Region3<T>::Unbounded = detail::gUnboundedRegion3<T>;

using Region3f = Region3<float>;
using Region3d = Region3<double>;
}
}
}

#endif
Loading

0 comments on commit 289dbc3

Please sign in to comment.