15 #ifndef OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
16 #define OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
23 #include <openscenario_preprocessor_msgs/srv/check_derivative_remained.hpp>
24 #include <openscenario_preprocessor_msgs/srv/derive.hpp>
25 #include <openscenario_preprocessor_msgs/srv/load.hpp>
26 #include <openscenario_preprocessor_msgs/srv/set_parameter.hpp>
27 #include <rclcpp/rclcpp.hpp>
37 path = load_request.path;
43 openscenario_preprocessor_msgs::srv::Derive::Response response;
44 response.path =
path.string();
49 std::filesystem::path
path;
62 [[nodiscard]]
bool validateXOSC(
const std::filesystem::path &,
bool);
64 rclcpp::Service<openscenario_preprocessor_msgs::srv::Load>::SharedPtr load_server;
66 rclcpp::Service<openscenario_preprocessor_msgs::srv::Derive>::SharedPtr derive_server;
68 rclcpp::Service<openscenario_preprocessor_msgs::srv::CheckDerivativeRemained>::SharedPtr
71 rclcpp::Service<openscenario_preprocessor_msgs::srv::SetParameter>::SharedPtr
74 std::deque<ScenarioSet> preprocessed_scenarios;
76 std::mutex preprocessed_scenarios_mutex;
78 std::unordered_map<std::string, std::string> override_parameters;
Definition: openscenario_preprocessor.hpp:55
Preprocessor(const rclcpp::NodeOptions &)
Definition: openscenario_preprocessor.cpp:23
Definition: openscenario_preprocessor.hpp:30
Request
Definition: behavior.hpp:25
Definition: openscenario_preprocessor.hpp:32
ScenarioSet(openscenario_preprocessor_msgs::srv::Load::Request &load_request)
Definition: openscenario_preprocessor.hpp:35
auto getDeriveResponse() -> openscenario_preprocessor_msgs::srv::Derive::Response
Definition: openscenario_preprocessor.hpp:41
std::filesystem::path path
Definition: openscenario_preprocessor.hpp:49
float frame_rate
Definition: openscenario_preprocessor.hpp:51