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_storage_id;
78 
79  std::shared_ptr<OpenScenario> script;
80 
81  std::list<std::shared_ptr<ScenarioDefinition>> scenarios;
82 
83  std::shared_ptr<rclcpp::TimerBase> timer;
84 
85  common::JUnit5 results;
86 
87  boost::variant<common::junit::Pass, common::junit::Failure, common::junit::Error> result;
88 
89  ExecutionTimer<> execution_timer;
90 
91  using Result = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
92 
93  bool waiting_for_engagement_to_be_completed = false; // NOTE: DIRTY HACK!!!
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 
105  auto engage() const -> void;
106 
107  auto engageable() const -> bool;
108 
109  auto engaged() const -> bool;
110 
112 
113  auto on_activate(const rclcpp_lifecycle::State &) -> Result override;
114 
115  auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override;
116 
117  auto on_configure(const rclcpp_lifecycle::State &) -> Result override;
118 
119  auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override;
120 
121  auto on_error(const rclcpp_lifecycle::State &) -> Result override;
122 
123  auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override;
124 
125  auto publishCurrentContext() const -> void;
126 
127  auto reset() -> void;
128 
129  template <typename T, typename... Ts>
130  auto set(Ts &&... xs) -> void
131  {
132  result = T(std::forward<decltype(xs)>(xs)...);
133 
134  results.name = boost::filesystem::path(osc_path).parent_path().parent_path().string();
135 
136  const auto suite_name = boost::filesystem::path(osc_path).parent_path().filename().string();
137 
138  const auto case_name = boost::filesystem::path(osc_path).stem().string();
139 
140  boost::apply_visitor(
141  overload(
142  [&](const common::junit::Pass & it) {
143  results.testsuite(suite_name).testcase(case_name).pass.push_back(it);
144  },
145  [&](const common::junit::Failure & it) {
146  results.testsuite(suite_name).testcase(case_name).failure.push_back(it);
147  },
148  [&](const common::junit::Error & it) {
149  results.testsuite(suite_name).testcase(case_name).error.push_back(it);
150  }),
151  result);
152 
153  results.write_to(
154  (boost::filesystem::path(output_directory) / "result.junit.xml").c_str(), " ");
155  }
156 
157  template <typename ExceptionHandler, typename Thunk>
158  auto withExceptionHandler(ExceptionHandler && handle, Thunk && thunk) -> decltype(auto)
159  {
160  try {
161  return thunk();
162  }
163 
164  catch (const SpecialAction<EXIT_SUCCESS> & action) // from CustomCommandAction::exitSuccess
165  {
166  set<common::junit::Pass>();
167  return handle(action);
168  }
169 
170  catch (const SpecialAction<EXIT_FAILURE> & action) // from CustomCommandAction::exitFailure
171  {
172  set<common::junit::Failure>("SimulationFailure", action.what());
173  return handle(action);
174  }
175 
176  catch (const AutowareError & error) {
177  set<common::junit::Error>("AutowareError", error.what());
178  return handle(error);
179  }
180 
181  catch (const SemanticError & error) {
182  set<common::junit::Error>("SemanticError", error.what());
183  return handle(error);
184  }
185 
186  catch (const SimulationError & error) {
187  set<common::junit::Error>("SimulationError", error.what());
188  return handle(error);
189  }
190 
191  catch (const SyntaxError & error) {
192  set<common::junit::Error>("SyntaxError", error.what());
193  return handle(error);
194  }
195 
196  catch (const std::exception & error) // NOTE: MUST BE LAST OF CATCH STATEMENTS.
197  {
198  set<common::junit::Error>("InternalError", error.what());
199  return handle(error);
200  }
201 
202  catch (...) // FINAL BARRIER
203  {
204  set<common::junit::Error>("UnknownError", "An unknown exception has occurred");
205  return handle();
206  }
207  }
208 };
209 } // namespace openscenario_interpreter
210 
211 #endif // OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
Definition: openscenario_interpreter.hpp:51
auto engage() const -> void
Definition: openscenario_interpreter.cpp:150
auto on_error(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:324
auto currentLocalFrameRate() const -> std::chrono::milliseconds
Definition: openscenario_interpreter.cpp:69
auto on_cleanup(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:317
auto engageable() const -> bool
Definition: openscenario_interpreter.cpp:162
auto on_shutdown(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:331
auto makeCurrentConfiguration() const -> traffic_simulator::Configuration
Definition: openscenario_interpreter.cpp:79
auto engaged() const -> bool
Definition: openscenario_interpreter.cpp:175
auto publishCurrentContext() const -> void
Definition: openscenario_interpreter.cpp:340
auto withExceptionHandler(ExceptionHandler &&handle, Thunk &&thunk) -> decltype(auto)
Definition: openscenario_interpreter.hpp:158
auto on_activate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:188
OPENSCENARIO_INTERPRETER_PUBLIC Interpreter(const rclcpp::NodeOptions &)
Definition: openscenario_interpreter.cpp:37
auto on_deactivate(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:310
auto set(Ts &&... xs) -> void
Definition: openscenario_interpreter.hpp:130
auto currentScenarioDefinition() const -> const std::shared_ptr< ScenarioDefinition > &
Definition: openscenario_interpreter.cpp:74
~Interpreter() override
Definition: openscenario_interpreter.cpp:67
auto on_configure(const rclcpp_lifecycle::State &) -> Result override
Definition: openscenario_interpreter.cpp:96
auto reset() -> void
Definition: openscenario_interpreter.cpp:358
Definition: custom_command_action.hpp:38
Definition: execution_timer.hpp:29
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