UFO 1.0.0
An Efficient Probabilistic 3D Mapping Framework That Embraces the Unknown
Loading...
Searching...
No Matches
frustum.hpp
1
42#ifndef UFO_GEOMETRY_FRUSTUM_HPP
43#define UFO_GEOMETRY_FRUSTUM_HPP
44
45#include <array>
46#include <ufo/geometry/plane.hpp>
47#include <ufo/numeric/vec.hpp>
48
49// STL
50#include <cmath>
51#include <concepts>
52#include <cstddef>
53#include <format>
54#include <limits>
55#include <ostream>
56
57namespace ufo
58{
67template <std::size_t Dim = 3, std::floating_point T = float>
68struct Frustum {
69 using value_type = T;
70
79 std::array<Plane<Dim, T>, 2 * Dim> planes;
80
84 constexpr Frustum() noexcept = default;
85
94 constexpr Frustum(Vec<2, T> const& far_right, Vec<2, T> const& far_left,
95 Vec<2, T> const& near_left, Vec<2, T> const& near_right)
96 requires(2 == Dim)
97 {
98 planes[0] = Plane<Dim, T>(near_left, far_left); // left
99 planes[1] = Plane<Dim, T>(far_right, near_right); // right
100 planes[2] = Plane<Dim, T>(near_right, near_left); // bottom/near
101 planes[3] = Plane<Dim, T>(far_left, far_right); // top/far
102 }
103
113 constexpr Frustum(Vec<2, T> const& pos, Vec<2, T> const& target, T fov, T near_dist,
114 T far_dist)
115 requires(2 == Dim)
116 {
117 auto dir = normalize(target - pos);
118 Vec<2, T> right_dir(dir.y(), -dir.x());
119 auto half_fov = fov * T(0.5);
120 auto half_width_near = near_dist * std::tan(half_fov);
121 auto half_width_far = far_dist * std::tan(half_fov);
122
123 Vec<2, T> far_right = pos + dir * far_dist + half_width_far * right_dir;
124 Vec<2, T> far_left = pos + dir * far_dist - half_width_far * right_dir;
125 Vec<2, T> near_left = pos + dir * near_dist - half_width_near * right_dir;
126 Vec<2, T> near_right = pos + dir * near_dist + half_width_near * right_dir;
127
128 planes[0] = Plane<Dim, T>(near_left, far_left);
129 planes[1] = Plane<Dim, T>(far_right, near_right);
130 planes[2] = Plane<Dim, T>(near_right, near_left);
131 planes[3] = Plane<Dim, T>(far_left, far_right);
132 }
133
146 constexpr Frustum(Vec<3, T> const& far_top_right, Vec<3, T> const& far_top_left,
147 Vec<3, T> const& far_bottom_left, Vec<3, T> const& far_bottom_right,
148 Vec<3, T> const& near_top_right, Vec<3, T> const& near_top_left,
149 Vec<3, T> const& near_bottom_left, Vec<3, T> const& near_bottom_right)
150 requires(3 == Dim)
151 {
152 planes[0] = Plane<Dim, T>(near_top_left, near_bottom_left, far_bottom_left); // left
153 planes[1] =
154 Plane<Dim, T>(near_bottom_right, near_top_right, far_bottom_right); // right
155 planes[2] =
156 Plane<Dim, T>(near_bottom_left, near_bottom_right, far_bottom_right); // bottom
157 planes[3] = Plane<Dim, T>(near_top_right, near_top_left, far_top_left); // top
158 planes[4] = Plane<Dim, T>(near_top_left, near_top_right, near_bottom_right); // near
159 planes[5] = Plane<Dim, T>(far_top_right, far_top_left, far_bottom_left); // far
160 }
161
173 constexpr Frustum(Vec<3, T> const& pos, Vec<3, T> const& target, Vec<3, T> const& up,
174 T vertical_fov, T horizontal_fov, T near_distance, T far_distance)
175 requires(3 == Dim)
176 {
177 T ratio = horizontal_fov / vertical_fov;
178
179 T tang = std::tan(vertical_fov * static_cast<T>(0.5));
180 T near_height = near_distance * tang;
181 T near_width = near_height * ratio;
182 T far_height = far_distance * tang;
183 T far_width = far_height * ratio;
184
185 auto Z = normalize(pos - target);
186 auto X = normalize(cross(up, Z));
187 auto Y = cross(Z, X);
188
189 auto nc = pos - Z * near_distance;
190 auto fc = pos - Z * far_distance;
191
192 auto ntl = nc + Y * near_height - X * near_width;
193 auto ntr = nc + Y * near_height + X * near_width;
194 auto nbl = nc - Y * near_height - X * near_width;
195 auto nbr = nc - Y * near_height + X * near_width;
196
197 auto ftl = fc + Y * far_height - X * far_width;
198 auto ftr = fc + Y * far_height + X * far_width;
199 auto fbl = fc - Y * far_height - X * far_width;
200 auto fbr = fc - Y * far_height + X * far_width;
201
202 planes[0] = Plane<Dim, T>(ntl, nbl, fbl); // left
203 planes[1] = Plane<Dim, T>(nbr, ntr, fbr); // right
204 planes[2] = Plane<Dim, T>(nbl, nbr, fbr); // bottom
205 planes[3] = Plane<Dim, T>(ntr, ntl, ftl); // top
206 planes[4] = Plane<Dim, T>(ntl, ntr, nbr); // near
207 planes[5] = Plane<Dim, T>(ftr, ftl, fbl); // far
208 }
209
213 constexpr Frustum(Frustum const&) noexcept = default;
214
221 template <std::convertible_to<T> U>
222 constexpr explicit Frustum(Frustum<Dim, U> const& other) noexcept
223 {
224 for (std::size_t i = 0; i < 2 * Dim; ++i) {
225 planes[i] = Plane<Dim, T>(other.planes[i]);
226 }
227 }
228
232 [[nodiscard]] static constexpr std::size_t dimension() noexcept { return Dim; }
233
240 [[nodiscard]] constexpr auto& operator[](this auto& self, std::size_t pos) noexcept
241 {
242 return self.planes[pos];
243 }
244
248 [[nodiscard]] bool operator==(Frustum const&) const = default;
249
254 [[nodiscard]] constexpr Vec<Dim, T> center() const noexcept
255 {
256 // This is just an approximation, better would be to find the vertices
257 Vec<Dim, T> c{};
258 for (auto const& p : planes) {
259 c += p.normal * p.distance;
260 }
261 return c / T(2 * Dim);
262 }
263
268 [[nodiscard]] constexpr AABB<Dim, T> aabb() const noexcept
269 {
270 // TODO: Implement exactly by finding vertices.
271 // For now, return infinite AABB as a safe placeholder if we don't have vertices.
272 return AABB<Dim, T>(Vec<Dim, T>(-std::numeric_limits<T>::infinity()),
273 Vec<Dim, T>(std::numeric_limits<T>::infinity()));
274 }
275
280 [[nodiscard]] constexpr bool isDegenerate() const noexcept
281 {
282 for (auto const& p : planes) {
283 if (p.isDegenerate()) {
284 return true;
285 }
286 }
287 return false;
288 }
289};
290
294template <std::size_t Dim, std::floating_point T>
295std::ostream& operator<<(std::ostream& out, Frustum<Dim, T> const& frustum)
296{
297 if constexpr (2 == Dim) {
298 return out << "Left: [" << frustum[0] << "], Right: [" << frustum[1] << "], Bottom: ["
299 << frustum[2] << "], Top: [" << frustum[3] << "]";
300 } else if constexpr (3 == Dim) {
301 return out << "Left: [" << frustum[0] << "], Right: [" << frustum[1] << "], Bottom: ["
302 << frustum[2] << "], Top: [" << frustum[3] << "], Near: [" << frustum[4]
303 << "], Far: [" << frustum[5] << "]";
304 } else {
305 out << "Planes: ";
306 for (std::size_t i = 0; i < 2 * Dim; ++i) {
307 out << "[" << frustum[i] << "]" << (i == 2 * Dim - 1 ? "" : ", ");
308 }
309 return out;
310 }
311}
312
313template <std::size_t Dim, std::floating_point T>
314using FrustumX = Frustum<Dim, T>;
315
316template <std::floating_point T>
317using Frustum1 = Frustum<1, T>;
318template <std::floating_point T>
319using Frustum2 = Frustum<2, T>;
320template <std::floating_point T>
321using Frustum3 = Frustum<3, T>;
322template <std::floating_point T>
323using Frustum4 = Frustum<4, T>;
324
325using Frustum1f = Frustum<1, float>;
326using Frustum2f = Frustum<2, float>;
327using Frustum3f = Frustum<3, float>;
328using Frustum4f = Frustum<4, float>;
329
330using Frustum1d = Frustum<1, double>;
331using Frustum2d = Frustum<2, double>;
332using Frustum3d = Frustum<3, double>;
333using Frustum4d = Frustum<4, double>;
334
335} // namespace ufo
336
337template <std::size_t Dim, std::floating_point T>
338 requires std::formattable<T, char>
339struct std::formatter<ufo::Frustum<Dim, T>> {
340 constexpr auto parse(std::format_parse_context& ctx) { return ctx.begin(); }
341
342 auto format(ufo::Frustum<Dim, T> const& frustum, std::format_context& ctx) const
343 {
344 if constexpr (2 == Dim) {
345 return std::format_to(ctx.out(), "Left: [{}], Right: [{}], Bottom: [{}], Top: [{}]",
346 frustum[0], frustum[1], frustum[2], frustum[3]);
347 } else if constexpr (3 == Dim) {
348 return std::format_to(
349 ctx.out(),
350 "Left: [{}], Right: [{}], Bottom: [{}], Top: [{}], Near: [{}], Far: [{}]",
351 frustum[0], frustum[1], frustum[2], frustum[3], frustum[4], frustum[5]);
352 } else {
353 std::format_to(ctx.out(), "Planes: ");
354 for (std::size_t i = 0; i < 2 * Dim; ++i) {
355 std::format_to(ctx.out(), "[{}]{}", frustum[i], (i == 2 * Dim - 1 ? "" : ", "));
356 }
357 return ctx.out();
358 }
359 }
360};
361
362#endif // UFO_GEOMETRY_FRUSTUM_HPP
All vision-related classes and functions.
Definition cloud.hpp:49
constexpr Quat< T > normalize(Quat< T > const &q) noexcept
Returns a unit quaternion in the same direction as q.
Definition quat.hpp:679
constexpr Quat< T > cross(Quat< T > const &q1, Quat< T > const &q2) noexcept
Computes the Hamilton cross product of two quaternions.
Definition quat.hpp:721
Axis-Aligned Bounding Box (AABB) in Dim-dimensional space.
Definition aabb.hpp:70
Frustum in Dim-dimensional space.
Definition frustum.hpp:68
constexpr Frustum(Vec< 2, T > const &pos, Vec< 2, T > const &target, T fov, T near_dist, T far_dist)
Constructs a 2D frustum from a camera-like setup.
Definition frustum.hpp:113
constexpr Frustum() noexcept=default
Default constructor.
constexpr AABB< Dim, T > aabb() const noexcept
Returns the AABB of the frustum.
Definition frustum.hpp:268
bool operator==(Frustum const &) const =default
Equality operator.
std::array< Plane< Dim, T >, 2 *Dim > planes
The planes defining the frustum.
Definition frustum.hpp:79
constexpr Frustum(Vec< 3, T > const &pos, Vec< 3, T > const &target, Vec< 3, T > const &up, T vertical_fov, T horizontal_fov, T near_distance, T far_distance)
Constructs a 3D frustum from a camera-like setup.
Definition frustum.hpp:173
constexpr Frustum(Vec< 3, T > const &far_top_right, Vec< 3, T > const &far_top_left, Vec< 3, T > const &far_bottom_left, Vec< 3, T > const &far_bottom_right, Vec< 3, T > const &near_top_right, Vec< 3, T > const &near_top_left, Vec< 3, T > const &near_bottom_left, Vec< 3, T > const &near_bottom_right)
Constructs a 3D frustum from eight points.
Definition frustum.hpp:146
static constexpr std::size_t dimension() noexcept
Returns the dimensionality of the frustum.
Definition frustum.hpp:232
constexpr Vec< Dim, T > center() const noexcept
Returns the center of the frustum.
Definition frustum.hpp:254
constexpr Frustum(Frustum< Dim, U > const &other) noexcept
Converting constructor from a frustum with a different scalar type.
Definition frustum.hpp:222
constexpr Frustum(Frustum const &) noexcept=default
Copy constructor.
constexpr auto & operator[](this auto &self, std::size_t pos) noexcept
Accesses the plane at position pos.
Definition frustum.hpp:240
constexpr bool isDegenerate() const noexcept
Returns whether the frustum is degenerate.
Definition frustum.hpp:280
Plane in space.
Definition plane.hpp:69
A fixed-size arithmetic vector of up to 4 dimensions.
Definition vec.hpp:76