Browse Source

Minor fixes and improvements to the linear algebra structs

master
C. J. Howard 1 year ago
parent
commit
b6b28dcb0c
15 changed files with 152 additions and 128 deletions
  1. +3
    -3
      src/ai/steering/behavior/flee.cpp
  2. +3
    -3
      src/ai/steering/behavior/seek.cpp
  3. +5
    -5
      src/game/load.cpp
  4. +4
    -4
      src/game/system/collision.cpp
  5. +1
    -1
      src/game/system/steering.cpp
  6. +4
    -4
      src/geom/intersection.cpp
  7. +3
    -3
      src/geom/primitive/hypersphere.hpp
  8. +1
    -1
      src/geom/primitive/intersection.hpp
  9. +1
    -1
      src/math/noise/simplex.hpp
  10. +3
    -3
      src/math/noise/voronoi.hpp
  11. +58
    -48
      src/math/quaternion.hpp
  12. +1
    -1
      src/math/se3.hpp
  13. +1
    -1
      src/math/transform-functions.hpp
  14. +63
    -49
      src/math/vector.hpp
  15. +1
    -1
      src/render/passes/sky-pass.cpp

+ 3
- 3
src/ai/steering/behavior/flee.cpp View File

@ -27,11 +27,11 @@ float3 flee(const agent& agent, const float3& target)
{
float3 force = {0, 0, 0};
const float3 difference = target - agent.position;
const float distance_squared = math::dot(difference, difference);
const float sqr_distance = math::dot(difference, difference);
if (distance_squared)
if (sqr_distance)
{
const float inverse_distance = 1.0f / std::sqrt(distance_squared);
const float inverse_distance = 1.0f / std::sqrt(sqr_distance);
force = difference * inverse_distance * agent.max_force;
force = agent.velocity - force;
}

+ 3
- 3
src/ai/steering/behavior/seek.cpp View File

@ -27,11 +27,11 @@ float3 seek(const agent& agent, const float3& target)
{
float3 force = {0, 0, 0};
const float3 difference = target - agent.position;
const float distance_squared = math::dot(difference, difference);
const float sqr_distance = math::dot(difference, difference);
if (distance_squared)
if (sqr_distance)
{
const float inverse_distance = 1.0f / std::sqrt(distance_squared);
const float inverse_distance = 1.0f / std::sqrt(sqr_distance);
force = difference * inverse_distance * agent.max_force;
force -= agent.velocity;
}

+ 5
- 5
src/game/load.cpp View File

@ -113,12 +113,12 @@ void biome(game::context& ctx, const std::filesystem::path& path)
// f2_sqr_distance,
// f2_displacement,
// f2_id
edge_sqr_distance
edge_sqr_distance(
] = math::noise::voronoi::f1_edge<float, 2>(position);
float f1_distance = std::sqrt(f1_sqr_distance);
//float f2_distance = std::sqrt(f2_sqr_distance);
float edge_distance = std::sqrt(edge_sqr_distance);
float f1_distance = std::sqrt(f1_sqr_distance();
//float f2_distance = std::sqrt(f2_sqr_distance();
float edge_distance = std::sqrt(edge_sqr_distance();
pixel = static_cast<unsigned char>(std::min(255.0f, f1_distance * 255.0f));
//pixel = static_cast<unsigned char>(id % 255);
@ -217,7 +217,7 @@ void biome(game::context& ctx, const std::filesystem::path& path)
f1_displacement,
f1_id
] = math::noise::voronoi::f1(position);
float f1_distance = std::sqrt(f1_sqr_distance);
float f1_distance = std::sqrt(f1_sqr_distance();
float y = f1_distance * 5.0f + fbm * 0.5f;
*/

+ 4
- 4
src/game/system/collision.cpp View File

@ -86,7 +86,7 @@ entity::id collision::pick_nearest(const geom::primitive::ray& ray, st
entity::id collision::pick_nearest(const float3& origin, const float3& normal, std::uint32_t flags) const
{
entity::id nearest_eid = entt::null;
float nearest_distance_squared = std::numeric_limits<float>::infinity();
float nearest_sqr_distance = std::numeric_limits<float>::infinity();
// Construct picking plane
const geom::primitive::plane<float> picking_plane = geom::primitive::plane<float>(origin, normal);
@ -108,13 +108,13 @@ entity::id collision::pick_nearest(const float3& origin, const float3& normal, s
return;
// Measure distance from picking plane origin to picking sphere center
const float distance_squared = math::distance_squared(picking_sphere_center, origin);
const float sqr_distance = math::sqr_distance(picking_sphere_center, origin);
// Check if entity is nearer than the current nearest entity
if (distance_squared < nearest_distance_squared)
if (sqr_distance < nearest_sqr_distance)
{
nearest_eid = entity_id;
nearest_distance_squared = distance_squared;
nearest_sqr_distance = sqr_distance;
}
}
);

+ 1
- 1
src/game/system/steering.cpp View File

@ -65,7 +65,7 @@ void steering::update(double t, double dt)
agent.velocity += agent.acceleration * static_cast<float>(dt);
// Limit speed
const float speed_squared = math::length_squared(agent.velocity);
const float speed_squared = math::sqr_length(agent.velocity);
if (speed_squared > agent.max_speed_squared)
{
const float speed = std::sqrt(speed_squared);

+ 4
- 4
src/geom/intersection.cpp View File

@ -171,17 +171,17 @@ bool aabb_aabb_intersection(const aabb& a, const aabb& b)
bool aabb_sphere_intersection(const aabb<float>& aabb, const float3& center, float radius)
{
float distance_squared = 0.0f;
float sqr_distance = 0.0f;
for (int i = 0; i < 3; ++i)
{
float v = center[i];
if (v < aabb.min_point[i])
distance_squared += (aabb.min_point[i] - v) * (aabb.min_point[i] - v);
sqr_distance += (aabb.min_point[i] - v) * (aabb.min_point[i] - v);
if (v > aabb.max_point[i])
distance_squared += (v - aabb.max_point[i]) * (v - aabb.max_point[i]);
sqr_distance += (v - aabb.max_point[i]) * (v - aabb.max_point[i]);
}
return (distance_squared <= (radius * radius));
return (sqr_distance <= (radius * radius));
}
} // namespace geom

+ 3
- 3
src/geom/primitive/hypersphere.hpp View File

@ -52,7 +52,7 @@ struct hypersphere
*/
constexpr bool contains(const vector_type& point) const noexcept
{
return math::distance_squared(center, point) <= radius * radius;
return math::sqr_distance(center, point) <= radius * radius;
}
/**
@ -68,7 +68,7 @@ struct hypersphere
if (containment_radius < T{0})
return false;
return math::distance_squared(center, other.center) <= containment_radius * containment_radius;
return math::sqr_distance(center, other.center) <= containment_radius * containment_radius;
}
/**
@ -93,7 +93,7 @@ struct hypersphere
constexpr bool intersects(const hypersphere& other) const noexcept
{
const T intersection_radius = radius + other.radius;
return math::distance_squared(center, other.center) <= intersection_radius * intersection_radius;
return math::sqr_distance(center, other.center) <= intersection_radius * intersection_radius;
}
/**

+ 1
- 1
src/geom/primitive/intersection.hpp View File

@ -117,7 +117,7 @@ std::optional> intersection(const ray& ray, const hypersp
{
const math::vector<T, N> displacement = ray.origin - hypersphere.center;
const T b = math::dot(displacement, ray.direction);
const T c = math::length_squared(displacement) - hypersphere.radius * hypersphere.radius;
const T c = math::sqr_length(displacement) - hypersphere.radius * hypersphere.radius;
T h = b * b - c;
if (h < T{0})

+ 1
- 1
src/math/noise/simplex.hpp View File

@ -202,7 +202,7 @@ T simplex
const vector<T, N> d = dx - (current_vertex - origin_vertex) + g * static_cast<T>(i);
// Calculate falloff
T t = falloff(length_squared(d));
T t = falloff(sqr_length(d));
if (t > T{0})
{
const hash::make_uint_t<T> gradient_index = hash(current_vertex)[0] % simplex_edges<T, N>.size();

+ 3
- 3
src/math/noise/voronoi.hpp View File

@ -160,7 +160,7 @@ f1
vector<T, N> displacement = (offset_i + offset_f) - position_f;
// Calculate square distance to the current cell center
T sqr_distance = length_squared(displacement);
T sqr_distance = sqr_length(displacement);
// Update F1 cell
if (sqr_distance < f1_sqr_distance)
@ -250,7 +250,7 @@ f1_edge
displacement_cache[i] = (offset_i + offset_f) - position_f;
// Calculate square distance to the current cell center
T sqr_distance = length_squared(displacement_cache[i]);
T sqr_distance = sqr_length(displacement_cache[i]);
// Update F1 cell
if (sqr_distance < f1_sqr_distance_center)
@ -377,7 +377,7 @@ f1_f2
vector<T, N> displacement = (offset_i + offset_f) - position_f;
// Calculate square distance to the current cell center
T sqr_distance = length_squared(displacement);
T sqr_distance = sqr_length(displacement);
// Update F1 and F2 cells
if (sqr_distance < f1_sqr_distance_center)

+ 58
- 48
src/math/quaternion.hpp View File

@ -30,7 +30,7 @@
namespace math {
/**
* A quaternion type is a tuple made of a scalar (real) part and vector (imaginary) part.
* Quaternion composed of a real scalar part and imaginary vector part.
*
* @tparam T Scalar type.
*/
@ -148,6 +148,31 @@ struct quaternion
return {static_cast<U>(r), vector<U, 3>(i)};
}
/**
* Constructs a matrix representing the rotation described the quaternion.
*
* @return Rotation matrix.
*/
constexpr explicit operator matrix_type() const noexcept
{
const T xx = x() * x();
const T xy = x() * y();
const T xz = x() * z();
const T xw = x() * w();
const T yy = y() * y();
const T yz = y() * z();
const T yw = y() * w();
const T zz = z() * z();
const T zw = z() * w();
return
{
T(1) - (yy + zz) * T(2), (xy + zw) * T(2), (xz - yw) * T(2),
(xy - zw) * T(2), T(1) - (xx + zz) * T(2), (yz + xw) * T(2),
(xz + yw) * T(2), (yz - xw) * T(2), T(1) - (xx + yy) * T(2)
};
}
/**
* Casts the quaternion to a 4-element vector, with the real part as the first element and the imaginary part as the following three elements.
*
@ -248,24 +273,24 @@ template
constexpr quaternion<T> div(T a, const quaternion<T>& b) noexcept;
/**
* Calculates the length of a quaternion.
* Calculates the inverse length of a quaternion.
*
* @param q Quaternion to calculate the length of.
* @param q Quaternion to calculate the inverse length of.
*
* @return Length of the quaternion.
* @return Inverse length of the quaternion.
*/
template <class T>
T length(const quaternion<T>& q);
T inv_length(const quaternion<T>& q);
/**
* Calculates the squared length of a quaternion. The squared length can be calculated faster than the length because a call to `std::sqrt` is saved.
* Calculates the length of a quaternion.
*
* @param q Quaternion to calculate the squared length of.
* @param q Quaternion to calculate the length of.
*
* @return Squared length of the quaternion.
* @return Length of the quaternion.
*/
template <class T>
constexpr T length_squared(const quaternion<T>& q) noexcept;
T length(const quaternion<T>& q);
/**
* Performs linear interpolation between two quaternions.
@ -290,16 +315,6 @@ constexpr quaternion lerp(const quaternion& a, const quaternion& b, T t
template <class T>
quaternion<T> look_rotation(const vector<T, 3>& forward, vector<T, 3> up);
/**
* Converts a quaternion to a rotation matrix.
*
* @param q Unit quaternion.
*
* @return Matrix representing the rotation described by `q`.
*/
template <class T>
constexpr matrix<T, 3, 3> matrix_cast(const quaternion<T>& q) noexcept;
/**
* Multiplies two quaternions.
*
@ -403,6 +418,16 @@ quaternion rotation(const vector& source, const vector& destinati
template <class T>
quaternion<T> slerp(const quaternion<T>& a, const quaternion<T>& b, T t, T error = T{1e-6});
/**
* Calculates the square length of a quaternion. The square length can be calculated faster than the length because a call to `std::sqrt` is saved.
*
* @param q Quaternion to calculate the square length of.
*
* @return Square length of the quaternion.
*/
template <class T>
constexpr T sqr_length(const quaternion<T>& q) noexcept;
/**
* Subtracts a quaternion from another quaternion.
*
@ -496,15 +521,15 @@ constexpr inline quaternion div(T a, const quaternion& b) noexcept
}
template <class T>
inline T length(const quaternion<T>& q)
inline T inv_length(const quaternion<T>& q)
{
return std::sqrt(length_squared(q));
return T{1} / length(q);
}
template <class T>
constexpr inline T length_squared(const quaternion<T>& q) noexcept
inline T length(const quaternion<T>& q)
{
return q.r * q.r + length_squared(q.i);
return std::sqrt(sqr_length(q));
}
template <class T>
@ -534,27 +559,6 @@ quaternion look_rotation(const vector& forward, vector up)
return normalize(quaternion_cast(m));
}
template <class T>
constexpr matrix<T, 3, 3> matrix_cast(const quaternion<T>& q) noexcept
{
const T xx = q.x() * q.x();
const T xy = q.x() * q.y();
const T xz = q.x() * q.z();
const T xw = q.x() * q.w();
const T yy = q.y() * q.y();
const T yz = q.y() * q.z();
const T yw = q.y() * q.w();
const T zz = q.z() * q.z();
const T zw = q.z() * q.w();
return
{
T(1) - (yy + zz) * T(2), (xy + zw) * T(2), (xz - yw) * T(2),
(xy - zw) * T(2), T(1) - (xx + zz) * T(2), (yz + xw) * T(2),
(xz + yw) * T(2), (yz - xw) * T(2), T(1) - (xx + yy) * T(2)
};
}
template <class T>
constexpr quaternion<T> mul(const quaternion<T>& a, const quaternion<T>& b) noexcept
{
@ -576,7 +580,7 @@ constexpr inline quaternion mul(const quaternion& a, T b) noexcept
template <class T>
constexpr vector<T, 3> mul(const quaternion<T>& a, const vector<T, 3>& b) noexcept
{
return a.i * dot(a.i, b) * T(2) + b * (a.r * a.r - length_squared(a.i)) + cross(a.i, b) * a.r * T(2);
return a.i * dot(a.i, b) * T(2) + b * (a.r * a.r - sqr_length(a.i)) + cross(a.i, b) * a.r * T(2);
}
template <class T>
@ -600,7 +604,7 @@ quaternion nlerp(const quaternion& a, const quaternion& b, T t)
template <class T>
inline quaternion<T> normalize(const quaternion<T>& q)
{
return mul(q, T(1) / length(q));
return mul(q, inv_length(q));
}
template <class T>
@ -634,6 +638,12 @@ quaternion slerp(const quaternion& a, const quaternion& b, T t, T error
return add(mul(a, std::cos(theta)), mul(c, std::sin(theta)));
}
template <class T>
constexpr inline T sqr_length(const quaternion<T>& q) noexcept
{
return q.r * q.r + sqr_length(q.i);
}
template <class T>
constexpr inline quaternion<T> sub(const quaternion<T>& a, const quaternion<T>& b) noexcept
{
@ -655,7 +665,7 @@ constexpr inline quaternion sub(T a, const quaternion& b) noexcept
template <class T>
void swing_twist(const quaternion<T>& q, const vector<T, 3>& a, quaternion<T>& qs, quaternion<T>& qt, T error)
{
if (length_squared(q.i) > error)
if (sqr_length(q.i) > error)
{
qt = normalize(quaternion<T>{q.w(), a * dot(a, q.i)});
qs = mul(q, conjugate(qt));
@ -666,7 +676,7 @@ void swing_twist(const quaternion& q, const vector& a, quaternion& q
const vector<T, 3> qa = mul(q, a);
const vector<T, 3> sa = cross(a, qa);
if (length_squared(sa) > error)
if (sqr_length(sa) > error)
qs = angle_axis(std::acos(dot(a, qa)), sa);
else
qs = quaternion<T>::identity();

+ 1
- 1
src/math/se3.hpp View File

@ -93,7 +93,7 @@ se3 se3::inverse() const
template <class T>
typename se3<T>::matrix_type se3<T>::matrix() const
{
matrix_type m = math::matrix<T, 4, 4>(math::matrix_cast<T>(r));
matrix_type m = math::matrix<T, 4, 4>(math::matrix<T, 3, 3>(r));
m[3].x() = t.x();
m[3].y() = t.y();

+ 1
- 1
src/math/transform-functions.hpp View File

@ -75,7 +75,7 @@ transform inverse(const transform& t)
template <class T>
matrix<T, 4, 4> matrix_cast(const transform<T>& t)
{
matrix<T, 4, 4> transformation = matrix<T, 4, 4>(matrix_cast(t.rotation));
matrix<T, 4, 4> transformation = matrix<T, 4, 4>(matrix<T, 3, 3>(t.rotation));
transformation[3] = {t.translation[0], t.translation[1], t.translation[2], T(1)};
return scale(transformation, t.scale);
}

+ 63
- 49
src/math/vector.hpp View File

@ -394,17 +394,6 @@ constexpr vector cross(const vector& x, const vector& y) noexc
template <class T, std::size_t N>
T distance(const vector<T, N>& p0, const vector<T, N>& p1);
/**
* Calculates the squared distance between two points. The squared distance can be calculated faster than the distance because a call to `std::sqrt` is saved.
*
* @param p0 First of two points.
* @param p1 Second of two points.
*
* @return Squared distance between the two points.
*/
template <class T, std::size_t N>
constexpr T distance_squared(const vector<T, N>& p0, const vector<T, N>& p1) noexcept;
/**
* Divides a vector by a value.
*
@ -503,24 +492,24 @@ template
constexpr vector<bool, N> greater_than_equal(const vector<T, N>& x, const vector<T, N>& y) noexcept;
/**
* Calculates the length of a vector.
* Calculates the inverse length of a vector.
*
* @param x Vector of which to calculate the length.
* @param x Vector of which to calculate the inverse length.
*
* @return Length of the vector.
* @return Inverse length of the vector.
*/
template <class T, std::size_t N>
T length(const vector<T, N>& x);
T inv_length(const vector<T, N>& x);
/**
* Calculates the squared length of a vector. The squared length can be calculated faster than the length because a call to `std::sqrt` is saved.
* Calculates the length of a vector.
*
* @param x Vector of which to calculate the squared length.
* @param x Vector of which to calculate the length.
*
* @return Squared length of the vector.
* @return Length of the vector.
*/
template <class T, std::size_t N>
constexpr T length_squared(const vector<T, N>& x) noexcept;
T length(const vector<T, N>& x);
/**
* Performs a element-wise less-than comparison of two vectors.
@ -691,6 +680,27 @@ constexpr vector round(const vector& x);
template <class T, std::size_t N>
constexpr vector<T, N> sign(const vector<T, N>& x);
/**
* Calculates the square distance between two points. The square distance can be calculated faster than the distance because a call to `std::sqrt` is saved.
*
* @param p0 First of two points.
* @param p1 Second of two points.
*
* @return Square distance between the two points.
*/
template <class T, std::size_t N>
constexpr T sqr_distance(const vector<T, N>& p0, const vector<T, N>& p1) noexcept;
/**
* Calculates the square length of a vector. The square length can be calculated faster than the length because a call to `std::sqrt` is saved.
*
* @param x Vector of which to calculate the square length.
*
* @return Square length of the vector.
*/
template <class T, std::size_t N>
constexpr T sqr_length(const vector<T, N>& x) noexcept;
/**
* Takes the square root of each element.
*
@ -819,13 +829,13 @@ constexpr inline bool any(const vector& x) noexcept
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> ceil(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::ceil(x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> ceil(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return ceil(x, std::make_index_sequence<N>{});
}
@ -859,8 +869,8 @@ template
vector<T, N> clamp_length(const vector<T, N>& x, T max_length)
{
static_assert(std::is_floating_point<T>::value);
T length2 = length_squared(x);
return (length2 > max_length * max_length) ? (x * max_length / std::sqrt(length2)) : x;
T length2 = sqr_length(x);
return (length2 > max_length * max_length) ? (x * (max_length / std::sqrt(length2))) : x;
}
template <class T>
@ -877,16 +887,9 @@ constexpr inline vector cross(const vector& x, const vector& y
template <class T, std::size_t N>
inline T distance(const vector<T, N>& p0, const vector<T, N>& p1)
{
static_assert(std::is_floating_point<T>::value);
return length(sub(p0, p1));
}
template <class T, std::size_t N>
constexpr inline T distance_squared(const vector<T, N>& p0, const vector<T, N>& p1) noexcept
{
return length_squared(sub(p0, p1));
}
/// @private
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> div(const vector<T, N>& x, const vector<T, N>& y, std::index_sequence<I...>) noexcept
@ -956,13 +959,13 @@ constexpr inline vector equal(const vector& x, const vector
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> floor(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::floor(x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> floor(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return floor(x, std::make_index_sequence<N>{});
}
@ -970,13 +973,13 @@ constexpr inline vector floor(const vector& x)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> fma(const vector<T, N>& x, const vector<T, N>& y, const vector<T, N>& z, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::fma(x[I], y[I], z[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> fma(const vector<T, N>& x, const vector<T, N>& y, const vector<T, N>& z)
{
static_assert(std::is_floating_point<T>::value);
return fma(x, y, z, std::make_index_sequence<N>{});
}
@ -984,13 +987,13 @@ constexpr inline vector fma(const vector& x, const vector& y,
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> fma(const vector<T, N>& x, T y, T z, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::fma(x[I], y, z)...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> fma(const vector<T, N>& x, T y, T z)
{
static_assert(std::is_floating_point<T>::value);
return fma(x, y, z, std::make_index_sequence<N>{});
}
@ -998,13 +1001,13 @@ constexpr inline vector fma(const vector& x, T y, T z)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> fract(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {x[I] - std::floor(x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> fract(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return fract(x, std::make_index_sequence<N>{});
}
@ -1035,16 +1038,16 @@ constexpr inline vector greater_than_equal(const vector& x, const
}
template <class T, std::size_t N>
inline T length(const vector<T, N>& x)
inline T inv_length(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return std::sqrt(dot(x, x));
return T{1} / length(x);
}
template <class T, std::size_t N>
constexpr inline T length_squared(const vector<T, N>& x) noexcept
inline T length(const vector<T, N>& x)
{
return dot(x, x);
static_assert(std::is_floating_point<T>::value);
return std::sqrt(sqr_length(x));
}
/// @private
@ -1115,13 +1118,13 @@ constexpr inline T min(const vector& x)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> mod(const vector<T, N>& x, const vector<T, N>& y, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::fmod(x[I], y[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> mod(const vector<T, N>& x, const vector<T, N>& y)
{
static_assert(std::is_floating_point<T>::value);
return mod(x, y, std::make_index_sequence<N>{});
}
@ -1129,13 +1132,13 @@ constexpr inline vector mod(const vector& x, const vector& y)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> mod(const vector<T, N>& x, T y, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::fmod(x[I], y)...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> mod(const vector<T, N>& x, T y)
{
static_assert(std::is_floating_point<T>::value);
return mod(x, y, std::make_index_sequence<N>{});
}
@ -1181,8 +1184,7 @@ constexpr inline vector negate(const vector& x) noexcept
template <class T, std::size_t N>
inline vector<T, N> normalize(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return mul(x, T{1} / length(x));
return mul(x, inv_length(x));
}
/// @private
@ -1215,13 +1217,13 @@ constexpr inline vector not_equal(const vector& x, const vector
template <class T, std::size_t N, std::size_t... I>
inline vector<T, N> pow(const vector<T, N>& x, const vector<T, N>& y, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::pow(x[I], y[I])...};
}
template <class T, std::size_t N>
inline vector<T, N> pow(const vector<T, N>& x, const vector<T, N>& y)
{
static_assert(std::is_floating_point<T>::value);
return pow(x, y, std::make_index_sequence<N>{});
}
@ -1229,13 +1231,13 @@ inline vector pow(const vector& x, const vector& y)
template <class T, std::size_t N, std::size_t... I>
inline vector<T, N> pow(const vector<T, N>& x, T y, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::pow(x[I], y)...};
}
template <class T, std::size_t N>
inline vector<T, N> pow(const vector<T, N>& x, T y)
{
static_assert(std::is_floating_point<T>::value);
return pow(x, y, std::make_index_sequence<N>{});
}
@ -1243,13 +1245,13 @@ inline vector pow(const vector& x, T y)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> round(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::round(x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> round(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return round(x, std::make_index_sequence<N>{});
}
@ -1257,28 +1259,40 @@ constexpr inline vector round(const vector& x)
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> sign(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::copysign(T{1}, x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> sign(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return sign(x, std::make_index_sequence<N>{});
}
template <class T, std::size_t N>
constexpr inline T sqr_distance(const vector<T, N>& p0, const vector<T, N>& p1) noexcept
{
return sqr_length(sub(p0, p1));
}
template <class T, std::size_t N>
constexpr inline T sqr_length(const vector<T, N>& x) noexcept
{
return dot(x, x);
}
/// @private
template <class T, std::size_t N, std::size_t... I>
inline vector<T, N> sqrt(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::sqrt(x[I])...};
}
template <class T, std::size_t N>
inline vector<T, N> sqrt(const vector<T, N>& x, const vector<T, N>& y)
{
static_assert(std::is_floating_point<T>::value);
return pow(x, std::make_index_sequence<N>{});
return sqrt(x, std::make_index_sequence<N>{});
}
/// @private
@ -1343,13 +1357,13 @@ constexpr inline vector swizzle(const vector& x) no
template <class T, std::size_t N, std::size_t... I>
constexpr inline vector<T, N> trunc(const vector<T, N>& x, std::index_sequence<I...>)
{
static_assert(std::is_floating_point<T>::value);
return {std::trunc(x[I])...};
}
template <class T, std::size_t N>
constexpr inline vector<T, N> trunc(const vector<T, N>& x)
{
static_assert(std::is_floating_point<T>::value);
return trunc(x, std::make_index_sequence<N>{});
}

+ 1
- 1
src/render/passes/sky-pass.cpp View File

@ -300,7 +300,7 @@ void sky_pass::render(const render::context& ctx, render::queue& queue) const
{
float star_distance = (clip_near + clip_far) * 0.5f;
model = float4x4(math::matrix_cast<float>(icrf_to_eus.r));
model = float4x4(float3x3(icrf_to_eus.r));
model = math::scale(model, {star_distance, star_distance, star_distance});
model_view = view * model;

Loading…
Cancel
Save