scenario_simulator_v2 C++ API
openscenario_preprocessor.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_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
16 #define OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
17 
18 #include <concealer/execute.hpp>
19 #include <deque>
20 #include <filesystem>
21 #include <memory>
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>
28 
30 {
32 {
33  ScenarioSet() = default;
34 
36  {
37  path = load_request.path;
38  frame_rate = load_request.frame_rate;
39  }
40 
41  auto getDeriveResponse() -> openscenario_preprocessor_msgs::srv::Derive::Response
42  {
43  openscenario_preprocessor_msgs::srv::Derive::Response response;
44  response.path = path.string();
45  response.frame_rate = frame_rate;
46  return response;
47  }
48 
49  std::filesystem::path path;
50 
51  float frame_rate;
52 };
53 
54 class Preprocessor : public rclcpp::Node
55 {
56 public:
57  explicit Preprocessor(const rclcpp::NodeOptions &);
58 
59 private:
60  void preprocessScenario(ScenarioSet &);
61 
62  [[nodiscard]] bool validateXOSC(const std::filesystem::path &, bool);
63 
64  rclcpp::Service<openscenario_preprocessor_msgs::srv::Load>::SharedPtr load_server;
65 
66  rclcpp::Service<openscenario_preprocessor_msgs::srv::Derive>::SharedPtr derive_server;
67 
68  rclcpp::Service<openscenario_preprocessor_msgs::srv::CheckDerivativeRemained>::SharedPtr
69  check_server;
70 
71  rclcpp::Service<openscenario_preprocessor_msgs::srv::SetParameter>::SharedPtr
72  set_parameter_server;
73 
74  std::deque<ScenarioSet> preprocessed_scenarios;
75 
76  std::mutex preprocessed_scenarios_mutex;
77 
78  std::unordered_map<std::string, std::string> override_parameters;
79 };
80 } // namespace openscenario_preprocessor
81 
82 #endif // OPENSCENARIO_PREPROCESSOR__OPENSCENARIO_PREPROCESSOR_HPP_
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