15 #ifndef OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
16 #define OPENSCENARIO_INTERPRETER__OPENSCENARIO_INTERPRETER_HPP_
18 #include <boost/variant.hpp>
20 #include <lifecycle_msgs/msg/state.hpp>
21 #include <lifecycle_msgs/msg/transition.hpp>
30 #include <openscenario_interpreter_msgs/msg/context.hpp>
31 #include <rclcpp/rclcpp.hpp>
32 #include <rclcpp_lifecycle/lifecycle_node.hpp>
35 #include <tier4_simulation_msgs/msg/user_defined_value.hpp>
38 #define INTERPRETER_INFO_STREAM(...) \
39 RCLCPP_INFO_STREAM(get_logger(), "\x1b[32m" << __VA_ARGS__ << "\x1b[0m")
43 #define INTERPRETER_ERROR_STREAM(...) \
44 RCLCPP_INFO_STREAM(get_logger(), "\x1b[1;31m" << __VA_ARGS__ << "\x1b[0m")
52 using Context = openscenario_interpreter_msgs::msg::Context;
54 const rclcpp_lifecycle::LifecyclePublisher<Context>::SharedPtr publisher_of_context;
56 rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
57 evaluate_time_publisher;
59 rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
60 update_time_publisher;
62 rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
63 output_time_publisher;
65 double local_frame_rate;
67 double local_real_time_factor;
73 bool publish_empty_context;
81 std::shared_ptr<OpenScenario> script;
83 std::list<std::shared_ptr<ScenarioDefinition>> scenarios;
85 std::shared_ptr<rclcpp::TimerBase> timer;
89 boost::variant<common::junit::Pass, common::junit::Failure, common::junit::Error> result;
93 using Result = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
107 auto on_activate(
const rclcpp_lifecycle::State &) -> Result
override;
109 auto on_cleanup(
const rclcpp_lifecycle::State &) -> Result
override;
111 auto on_configure(
const rclcpp_lifecycle::State &) -> Result
override;
113 auto on_deactivate(
const rclcpp_lifecycle::State &) -> Result
override;
115 auto on_error(
const rclcpp_lifecycle::State &) -> Result
override;
117 auto on_shutdown(
const rclcpp_lifecycle::State &) -> Result
override;
121 auto reset() -> void;
123 template <
typename T,
typename... Ts>
126 result = T(std::forward<decltype(
xs)>(
xs)...);
128 results.
name = boost::filesystem::path(osc_path).parent_path().parent_path().string();
130 const auto suite_name = boost::filesystem::path(osc_path).parent_path().filename().string();
132 const auto case_name = boost::filesystem::path(osc_path).stem().string();
134 boost::apply_visitor(
137 results.
testsuite(suite_name).testcase(case_name).pass.push_back(it);
140 results.
testsuite(suite_name).testcase(case_name).failure.push_back(it);
143 results.
testsuite(suite_name).testcase(case_name).error.push_back(it);
148 (boost::filesystem::path(output_directory) /
"result.junit.xml").c_str(),
" ");
150 execution_timer.
save(boost::filesystem::path(output_directory) /
"execution_timer.json");
153 template <
typename ExceptionHandler,
typename Thunk>
162 set<common::junit::Pass>();
163 return handle(action);
168 set<common::junit::Failure>(
"SimulationFailure", action.what());
169 return handle(action);
172 catch (
const AutowareError & error) {
173 set<common::junit::Error>(
"AutowareError", error.what());
174 return handle(error);
177 catch (
const SemanticError & error) {
178 set<common::junit::Error>(
"SemanticError", error.what());
179 return handle(error);
182 catch (
const SimulationError & error) {
183 set<common::junit::Error>(
"SimulationError", error.what());
184 return handle(error);
187 catch (
const SyntaxError & error) {
188 set<common::junit::Error>(
"SyntaxError", error.what());
189 return handle(error);
192 catch (
const std::exception & error)
194 set<common::junit::Error>(
"InternalError", error.what());
195 return handle(error);
200 set<common::junit::Error>(
"UnknownError",
"An unknown exception has occurred");
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: simulator_core.hpp:535
Definition: simulator_core.hpp:636
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: 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