scenario_simulator_v2 C++ API
openscenario_interpreter.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__OPENSCENARIO_INTERPRETER_HPP_
16 #define OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
17 
18 #include <chrono>
19 #include <lifecycle_msgs/msg/state.hpp>
20 #include <lifecycle_msgs/msg/transition.hpp>
21 #include <memory>
29 #include <openscenario_interpreter_msgs/msg/context.hpp>
30 #include <rclcpp/rclcpp.hpp>
31 #include <rclcpp_lifecycle/lifecycle_node.hpp>
33 #include <simple_junit/junit5.hpp>
34 #include <tier4_simulation_msgs/msg/user_defined_value.hpp>
35 #include <utility>
36 
37 #define INTERPRETER_INFO_STREAM(...) \
38  RCLCPP_INFO_STREAM(get_logger(), "\x1b[32m" << __VA_ARGS__ << "\x1b[0m")
39 
40 // NOTE: Error on simulation is not error of the interpreter; so we print error messages into
41 // INFO_STREAM.
42 #define INTERPRETER_ERROR_STREAM(...) \
43  RCLCPP_INFO_STREAM(get_logger(), "\x1b[1;31m" << __VA_ARGS__ << "\x1b[0m")
44 
46 {
47 class Interpreter : public rclcpp_lifecycle::LifecycleNode,
50 {
52  static inline constexpr std::chrono::seconds simulator_core_shutdown_threshold{30};
53 
54  using Context = openscenario_interpreter_msgs::msg::Context;
55 
56  const rclcpp_lifecycle::LifecyclePublisher<Context>::SharedPtr publisher_of_context;
57 
58  rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
59  evaluate_time_publisher;
60 
61  rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
62  update_time_publisher;
63 
64  rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
65  output_time_publisher;
66 
67  double local_frame_rate;
68 
69  double local_real_time_factor;
70 
71  String osc_path;
72 
73  String output_directory;
74 
75  bool publish_empty_context;
76 
77  bool record;
78 
79  String record_option;
80 
81  String record_storage_id;
82 
83  std::shared_ptr<OpenScenario> script;
84 
85  std::list<std::shared_ptr<ScenarioDefinition>> scenarios;
86 
87  std::shared_ptr<rclcpp::TimerBase> timer;
88 
89  common::JUnit5 results;
90 
91  std::variant<common::junit::Pass, common::junit::Failure, common::junit::Error> result;
92 
93  ExecutionTimer<> execution_timer;
94 
95  using Result = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
96 
97 public:
99  explicit Interpreter(const rclcpp::NodeOptions &);
100 
101  ~Interpreter() override;
102 
103  auto currentLocalFrameRate() const -> std::chrono::milliseconds;
104 
105  auto currentScenarioDefinition() const -> const std::shared_ptr<ScenarioDefinition> &;
106 
108 
109  auto on_activate(const rclcpp_lifecycle::State &) -> Result override;
110 
111  auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override;
112 
113  auto on_configure(const rclcpp_lifecycle::State &) -> Result override;
114 
115  auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override;
116 
117  auto on_error(const rclcpp_lifecycle::State &) -> Result override;
118 
119  auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override;
120 
121  auto publishCurrentContext() const -> void;
122 
123  auto reset() -> void;
124 
125  template <typename T, typename... Ts>
126  auto set(Ts &&... xs) -> void
127  {
128  result = T(std::forward<decltype(xs)>(xs)...);
129 
130  results.name = std::filesystem::path(osc_path).parent_path().parent_path().string();
131 
132  const auto suite_name = std::filesystem::path(osc_path).parent_path().filename().string();
133 
134  const auto case_name = std::filesystem::path(osc_path).stem().string();
135 
136  std::visit(
137  overload(
138  [&](const common::junit::Pass & it) {
139  results.testsuite(suite_name).testcase(case_name).pass.push_back(it);
140  },
141  [&](const common::junit::Failure & it) {
142  results.testsuite(suite_name).testcase(case_name).failure.push_back(it);
143  },
144  [&](const common::junit::Error & it) {
145  results.testsuite(suite_name).testcase(case_name).error.push_back(it);
146  }),
147  result);
148 
149  results.write_to((std::filesystem::path(output_directory) / "result.junit.xml").c_str(), " ");
150 
151  execution_timer.save(std::filesystem::path(output_directory) / "execution_timer.json");
152  }
153 
154  template <typename ExceptionHandler, typename Thunk>
155  auto withExceptionHandler(ExceptionHandler && handle, Thunk && thunk) -> decltype(auto)
156  {
157  try {
158  return thunk();
159  }
160 
161  catch (const SpecialAction<EXIT_SUCCESS> & action) // from CustomCommandAction::exitSuccess
162  {
163  set<common::junit::Pass>();
164  return handle(action);
165  }
166 
167  catch (const SpecialAction<EXIT_FAILURE> & action) // from CustomCommandAction::exitFailure
168  {
169  set<common::junit::Failure>("SimulationFailure", action.what());
170  return handle(action);
171  }
172 
173  catch (const AutowareError & error) {
174  set<common::junit::Error>("AutowareError", error.what());
175  return handle(error);
176  }
177 
178  catch (const SemanticError & error) {
179  set<common::junit::Error>("SemanticError", error.what());
180  return handle(error);
181  }
182 
183  catch (const SimulationError & error) {
184  set<common::junit::Error>("SimulationError", error.what());
185  return handle(error);
186  }
187 
188  catch (const SyntaxError & error) {
189  set<common::junit::Error>("SyntaxError", error.what());
190  return handle(error);
191  }
192 
193  catch (const std::exception & error) // NOTE: MUST BE LAST OF CATCH STATEMENTS.
194  {
195  set<common::junit::Error>("InternalError", error.what());
196  return handle(error);
197  }
198 
199  catch (...) // FINAL BARRIER
200  {
201  set<common::junit::Error>("UnknownError", "An unknown exception has occurred");
202  return handle();
203  }
204  }
205 };
206 } // namespace openscenario_interpreter
207 
208 #endif // OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
Definition: openscenario_interpreter.hpp:50
auto on_error(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:313
auto currentLocalFrameRate() const -> std::chrono::milliseconds
Definition: openscenario_interpreter.cpp:72
auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:306
auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:320
auto makeCurrentConfiguration() const -> traffic_simulator::Configuration
Definition: openscenario_interpreter.cpp:82
auto publishCurrentContext() const -> void
Definition: openscenario_interpreter.cpp:330
auto withExceptionHandler(ExceptionHandler &&handle, Thunk &&thunk) -> decltype(auto)
Definition: openscenario_interpreter.hpp:155
auto on_activate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:153
OPENSCENARIO_INTERPRETER_PUBLIC Interpreter(const rclcpp::NodeOptions &)
Definition: openscenario_interpreter.cpp:38
auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:299
auto set(Ts &&... xs) -> void
Definition: openscenario_interpreter.hpp:126
auto currentScenarioDefinition() const -> const std::shared_ptr< ScenarioDefinition > &
Definition: openscenario_interpreter.cpp:77
~Interpreter() override
Definition: openscenario_interpreter.cpp:70
auto on_configure(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:99
auto reset() -> void
Definition: openscenario_interpreter.cpp:348
Definition: custom_command_action.hpp:38
Definition: execution_timer.hpp:40
auto save(const std::filesystem::path &output_file) -> void
Definition: execution_timer.hpp:60
std::string String
Definition: string.hpp:24
constexpr auto overload(Ts &&... xs) -> typename utility::overloaded< typename std::decay< Ts >::type... >
Definition: overload.hpp:51
Definition: hypot.hpp:22
Definition: junit5.hpp:25
#define OPENSCENARIO_INTERPRETER_PUBLIC
Definition: visibility.hpp:49
Definition: junit5.hpp:88
Definition: junit5.hpp:51
Definition: junit5.hpp:34
Definition: junit5.hpp:336
xs::string name
Definition: junit5.hpp:337
auto write_to(Ts &&... xs) const
Definition: junit5.hpp:381
auto testsuite(const xs::string &name) -> auto &
Definition: junit5.hpp:341
Definition: custom_command_action.hpp:32
Definition: configuration.hpp:30