scenario_simulator_v2 C++ API
hypot.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 OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_
16 #define OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_
17 
18 #include <cmath>
19 #include <rclcpp/rclcpp.hpp>
20 
22 {
23 inline namespace cmath
24 {
25 /*
26  @todo: after checking all the scenario work well with
27  consider_pose_by_road_slope = true, remove this function and use
28  std::hypot(x, y, z)
29 */
30 template <typename T>
31 auto hypot(T x, T y, T z)
32 {
33  static const auto consider_pose_by_road_slope = []() {
34  auto node = rclcpp::Node("get_parameter", "simulation");
35  node.declare_parameter("consider_pose_by_road_slope", false);
36  return node.get_parameter("consider_pose_by_road_slope").as_bool();
37  }();
38 
39  return consider_pose_by_road_slope ? std::hypot(x, y, z) : std::hypot(x, y);
40 }
41 } // namespace cmath
42 } // namespace openscenario_interpreter
43 
44 #endif // OPENSCENARIO_INTERPRETER__CMATH__HYPOT_HPP_
auto hypot(T x, T y, T z)
Definition: hypot.hpp:31
Definition: hypot.hpp:22