scenario_simulator_v2 C++ API
internal_angle.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__INTERNAL_ANGLE_HPP_
16 #define GEOMETRY__VECTOR3__INTERNAL_ANGLE_HPP_
17 
22 
23 namespace math
24 {
25 namespace geometry
26 {
27 template <
28  typename T, typename U,
29  std::enable_if_t<std::conjunction_v<IsLikeVector3<T>, IsLikeVector3<U>>, std::nullptr_t> =
30  nullptr>
31 auto getInternalAngle(const T & v0, const U & v1)
32 {
33  const auto val = innerProduct(v0, v1) / (norm(v0) * norm(v1));
34  if (-1 <= val && val <= 1) {
35  return std::acos(val);
36  }
38  "value of v0*v1/(size(v0)*size(v1)) in vector v0 : ", v0.x, ",", v0.y, ",", v0.z,
39  " and v1 : ", v1.x, ",", v1.y, ",", v1.z, "is out of range, value = ", val);
40 }
41 } // namespace geometry
42 } // namespace math
43 
44 #endif // GEOMETRY__VECTOR3__INTERNAL_ANGLE_HPP_
#define THROW_SIMULATION_ERROR(...)
Definition: exception.hpp:60
auto norm(const T &v)
Definition: norm.hpp:25
auto getInternalAngle(const T &v0, const U &v1)
Definition: internal_angle.hpp:31
auto innerProduct(const T &v0, const U &v1)
Definition: inner_product.hpp:28
Definition: bounding_box.hpp:32