15 #ifndef GEOMETRY__VECTOR3__SCALAR_TO_DIRECTION_VECTOR_HPP_
16 #define GEOMETRY__VECTOR3__SCALAR_TO_DIRECTION_VECTOR_HPP_
21 #include <type_traits>
33 typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> =
nullptr>
39 std::cos(pitch) * std::cos(yaw) * magnitude, std::cos(pitch) * std::sin(yaw) * magnitude,
40 std::sin(pitch) * magnitude);
auto convertQuaternionToEulerAngle(const T &q)
Definition: quaternion_to_euler.hpp:30
auto vector3(const T &x, const U &y, const V &z)
Definition: vector3.hpp:30
auto scalarToDirectionVector(const double magnitude, const T &orientation)
converts scalar magnitude to 3D directional vector
Definition: scalar_to_direction_vector.hpp:34
Definition: bounding_box.hpp:32