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 <boost/variant.hpp>
19 #include <chrono>
20 #include <lifecycle_msgs/msg/state.hpp>
21 #include <lifecycle_msgs/msg/transition.hpp>
22 #include <memory>
30 #include <openscenario_interpreter_msgs/msg/context.hpp>
31 #include <rclcpp/rclcpp.hpp>
32 #include <rclcpp_lifecycle/lifecycle_node.hpp>
34 #include <simple_junit/junit5.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 {
51  using Context = openscenario_interpreter_msgs::msg::Context;
52 
53  const rclcpp_lifecycle::LifecyclePublisher<Context>::SharedPtr publisher_of_context;
54 
55  double local_frame_rate;
56 
57  double local_real_time_factor;
58 
59  String osc_path;
60 
61  String output_directory;
62 
63  bool record;
64 
65  std::shared_ptr<OpenScenario> script;
66 
67  std::list<std::shared_ptr<ScenarioDefinition>> scenarios;
68 
69  std::shared_ptr<rclcpp::TimerBase> timer;
70 
71  common::JUnit5 results;
72 
73  boost::variant<common::junit::Pass, common::junit::Failure, common::junit::Error> result;
74 
75  ExecutionTimer<> execution_timer;
76 
77  using Result = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
78 
79  bool waiting_for_engagement_to_be_completed = false; // NOTE: DIRTY HACK!!!
80 
81 public:
83  explicit Interpreter(const rclcpp::NodeOptions &);
84 
85  ~Interpreter() override;
86 
87  auto currentLocalFrameRate() const -> std::chrono::milliseconds;
88 
89  auto currentScenarioDefinition() const -> const std::shared_ptr<ScenarioDefinition> &;
90 
91  auto engage() const -> void;
92 
93  auto engageable() const -> bool;
94 
95  auto engaged() const -> bool;
96 
98 
99  auto on_activate(const rclcpp_lifecycle::State &) -> Result override;
100 
101  auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override;
102 
103  auto on_configure(const rclcpp_lifecycle::State &) -> Result override;
104 
105  auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override;
106 
107  auto on_error(const rclcpp_lifecycle::State &) -> Result override;
108 
109  auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override;
110 
111  auto publishCurrentContext() const -> void;
112 
113  auto reset() -> void;
114 
115  template <typename T, typename... Ts>
116  auto set(Ts &&... xs) -> void
117  {
118  result = T(std::forward<decltype(xs)>(xs)...);
119 
120  results.name = boost::filesystem::path(osc_path).parent_path().parent_path().string();
121 
122  const auto suite_name = boost::filesystem::path(osc_path).parent_path().filename().string();
123 
124  const auto case_name = boost::filesystem::path(osc_path).stem().string();
125 
126  boost::apply_visitor(
127  overload(
128  [&](const common::junit::Pass & it) {
129  results.testsuite(suite_name).testcase(case_name).pass.push_back(it);
130  },
131  [&](const common::junit::Failure & it) {
132  results.testsuite(suite_name).testcase(case_name).failure.push_back(it);
133  },
134  [&](const common::junit::Error & it) {
135  results.testsuite(suite_name).testcase(case_name).error.push_back(it);
136  }),
137  result);
138 
139  results.write_to(
140  (boost::filesystem::path(output_directory) / "result.junit.xml").c_str(), " ");
141  }
142 
143  template <typename ExceptionHandler, typename Thunk>
144  auto withExceptionHandler(ExceptionHandler && handle, Thunk && thunk) -> decltype(auto)
145  {
146  try {
147  return thunk();
148  }
149 
150  catch (const SpecialAction<EXIT_SUCCESS> & action) // from CustomCommandAction::exitSuccess
151  {
152  set<common::junit::Pass>();
153  return handle(action);
154  }
155 
156  catch (const SpecialAction<EXIT_FAILURE> & action) // from CustomCommandAction::exitFailure
157  {
158  set<common::junit::Failure>("SimulationFailure", action.what());
159  return handle(action);
160  }
161 
162  catch (const AutowareError & error) {
163  set<common::junit::Error>("AutowareError", error.what());
164  return handle(error);
165  }
166 
167  catch (const SemanticError & error) {
168  set<common::junit::Error>("SemanticError", error.what());
169  return handle(error);
170  }
171 
172  catch (const SimulationError & error) {
173  set<common::junit::Error>("SimulationError", error.what());
174  return handle(error);
175  }
176 
177  catch (const SyntaxError & error) {
178  set<common::junit::Error>("SyntaxError", error.what());
179  return handle(error);
180  }
181 
182  catch (const std::exception & error) // NOTE: MUST BE LAST OF CATCH STATEMENTS.
183  {
184  set<common::junit::Error>("InternalError", error.what());
185  return handle(error);
186  }
187 
188  catch (...) // FINAL BARRIER
189  {
190  set<common::junit::Error>("UnknownError", "An unknown exception has occurred");
191  return handle();
192  }
193  }
194 
195  template <typename TimeoutHandler, typename Thunk>
196  auto withTimeoutHandler(TimeoutHandler && handle, Thunk && thunk) -> decltype(auto)
197  {
198  if (const auto time = execution_timer.invoke("", thunk); currentLocalFrameRate() < time) {
199  handle(execution_timer.getStatistics(""));
200  }
201  }
202 
204  {
205  /*
206  Ideally, the scenario should be terminated with an error if the total
207  time for the ScenarioDefinition evaluation and the traffic_simulator's
208  updateFrame exceeds the time allowed for a single frame. However, we
209  have found that many users are in environments where it is not possible
210  to run the simulator stably at 30 FPS (the default setting) while
211  running Autoware. In order to prioritize comfortable daily use, we
212  decided to give up full reproducibility of the scenario and only provide
213  warnings.
214  */
215 
216  return [this](const auto & statistics) {
217  RCLCPP_WARN_STREAM(
218  get_logger(),
219  "Your machine is not powerful enough to run the scenario at the specified frame rate ("
220  << local_frame_rate << " Hz). We recommend that you reduce the frame rate to "
221  << 1000.0 / statistics.template max<std::chrono::milliseconds>().count() << " or less.");
222  };
223  }
224 };
225 } // namespace openscenario_interpreter
226 
227 #endif // OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
Definition: openscenario_interpreter.hpp:50
auto engage() const -> void
Definition: openscenario_interpreter.cpp:125
auto on_error(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:254
auto currentLocalFrameRate() const -> std::chrono::milliseconds
Definition: openscenario_interpreter.cpp:53
auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:247
auto defaultTimeoutHandler() const
Definition: openscenario_interpreter.hpp:203
auto engageable() const -> bool
Definition: openscenario_interpreter.cpp:136
auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:261
auto makeCurrentConfiguration() const -> traffic_simulator::Configuration
Definition: openscenario_interpreter.cpp:63
auto engaged() const -> bool
Definition: openscenario_interpreter.cpp:148
auto publishCurrentContext() const -> void
Definition: openscenario_interpreter.cpp:270
auto withTimeoutHandler(TimeoutHandler &&handle, Thunk &&thunk) -> decltype(auto)
Definition: openscenario_interpreter.hpp:196
auto withExceptionHandler(ExceptionHandler &&handle, Thunk &&thunk) -> decltype(auto)
Definition: openscenario_interpreter.hpp:144
auto on_activate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:160
OPENSCENARIO_INTERPRETER_PUBLIC Interpreter(const rclcpp::NodeOptions &)
Definition: openscenario_interpreter.cpp:35
auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:240
auto set(Ts &&... xs) -> void
Definition: openscenario_interpreter.hpp:116
auto currentScenarioDefinition() const -> const std::shared_ptr< ScenarioDefinition > &
Definition: openscenario_interpreter.cpp:58
~Interpreter() override
Definition: openscenario_interpreter.cpp:51
auto on_configure(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:82
auto reset() -> void
Definition: openscenario_interpreter.cpp:283
Definition: custom_command_action.hpp:38
Definition: execution_timer.hpp:29
auto invoke(const std::string &tag, Thunk &&thunk)
Definition: execution_timer.hpp:98
auto getStatistics(const std::string &tag) -> const auto &
Definition: execution_timer.hpp:113
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: escape_sequence.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