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 <openscenario_preprocessor_msgs/srv/set_parameter.hpp> 
   26 #include <rclcpp/rclcpp.hpp> 
   36     path = load_request.path;
 
   42     openscenario_preprocessor_msgs::srv::Derive::Response response;
 
   43     response.path = 
path.string();
 
   48   boost::filesystem::path 
path;
 
   61   [[nodiscard]] 
bool validateXOSC(
const boost::filesystem::path &, 
bool);
 
   63   rclcpp::Service<openscenario_preprocessor_msgs::srv::Load>::SharedPtr load_server;
 
   65   rclcpp::Service<openscenario_preprocessor_msgs::srv::Derive>::SharedPtr derive_server;
 
   67   rclcpp::Service<openscenario_preprocessor_msgs::srv::CheckDerivativeRemained>::SharedPtr
 
   70   rclcpp::Service<openscenario_preprocessor_msgs::srv::SetParameter>::SharedPtr
 
   73   std::deque<ScenarioSet> preprocessed_scenarios;
 
   75   std::mutex preprocessed_scenarios_mutex;
 
   77   std::unordered_map<std::string, std::string> override_parameters;
 
Definition: openscenario_preprocessor.hpp:54
Preprocessor(const rclcpp::NodeOptions &)
Definition: openscenario_preprocessor.cpp:23
Definition: openscenario_preprocessor.hpp:29
Request
Definition: behavior.hpp:25
Definition: openscenario_preprocessor.hpp:31
ScenarioSet(openscenario_preprocessor_msgs::srv::Load::Request &load_request)
Definition: openscenario_preprocessor.hpp:34
boost::filesystem::path path
Definition: openscenario_preprocessor.hpp:48
auto getDeriveResponse() -> openscenario_preprocessor_msgs::srv::Derive::Response
Definition: openscenario_preprocessor.hpp:40
float frame_rate
Definition: openscenario_preprocessor.hpp:50