scenario_simulator_v2 C++ API
scalar_to_direction_vector.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef GEOMETRY__VECTOR3__SCALAR_TO_DIRECTION_VECTOR_HPP_
16 #define GEOMETRY__VECTOR3__SCALAR_TO_DIRECTION_VECTOR_HPP_
17 
21 #include <type_traits>
22 
23 namespace math
24 {
25 namespace geometry
26 {
32 template <
33  typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> = nullptr>
34 auto scalarToDirectionVector(const double magnitude, const T & orientation)
35 {
36  const auto pitch = -convertQuaternionToEulerAngle(orientation).y;
37  const auto yaw = convertQuaternionToEulerAngle(orientation).z;
38  return vector3(
39  std::cos(pitch) * std::cos(yaw) * magnitude, std::cos(pitch) * std::sin(yaw) * magnitude,
40  std::sin(pitch) * magnitude);
41 }
42 } // namespace geometry
43 } // namespace math
44 
45 #endif // GEOMETRY__VECTOR3__SCALAR_TO_DIRECTION_VECTOR_HPP_
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