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