15 #ifndef OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
16 #define OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
22 #include <openscenario_preprocessor_msgs/srv/check_derivative_remained.hpp>
23 #include <openscenario_preprocessor_msgs/srv/derive.hpp>
24 #include <openscenario_preprocessor_msgs/srv/load.hpp>
25 #include <rclcpp/rclcpp.hpp>
35 path = load_request.path;
41 openscenario_preprocessor_msgs::srv::Derive::Response response;
60 [[nodiscard]]
bool validateXOSC(
const boost::filesystem::path &,
bool);
62 rclcpp::Service<openscenario_preprocessor_msgs::srv::Load>::SharedPtr load_server;
64 rclcpp::Service<openscenario_preprocessor_msgs::srv::Derive>::SharedPtr derive_server;
66 rclcpp::Service<openscenario_preprocessor_msgs::srv::CheckDerivativeRemained>::SharedPtr
69 std::deque<ScenarioSet> preprocessed_scenarios;
71 std::mutex preprocessed_scenarios_mutex;
Definition: openscenario_preprocessor.hpp:53
Preprocessor(const rclcpp::NodeOptions &)
Definition: openscenario_preprocessor.cpp:23
Definition: openscenario_preprocessor.hpp:28
Request
Definition: behavior.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: openscenario_preprocessor.hpp:30
std::string path
Definition: openscenario_preprocessor.hpp:47
ScenarioSet(openscenario_preprocessor_msgs::srv::Load::Request &load_request)
Definition: openscenario_preprocessor.hpp:33
auto getDeriveResponse() -> openscenario_preprocessor_msgs::srv::Derive::Response
Definition: openscenario_preprocessor.hpp:39
float frame_rate
Definition: openscenario_preprocessor.hpp:49