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