scenario_simulator_v2 C++ API
cpp_scenario_node.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 CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
16 #define CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
17 
18 #include <limits>
19 #include <memory>
20 #include <rclcpp/rclcpp.hpp>
21 #include <simple_junit/junit5.hpp>
22 #include <string>
24 #include <vector>
25 
27 {
28 enum class Result { SUCCESS = 0, FAILURE = 1 };
29 
30 class CppScenarioNode : public rclcpp::Node
31 {
32 public:
33  explicit CppScenarioNode(
34  const std::string & node_name, const std::string & map_path,
35  const std::string & lanelet2_map_file, const std::string & scenario_filename,
36  const bool verbose, const rclcpp::NodeOptions & option,
37  const std::set<std::uint8_t> & auto_sink_entity_types = {});
38  void start(const bool start_scenario_clock = true);
39  void stop(Result result, const std::string & description = "");
40  void expectThrow() { exception_expect_ = true; }
41  void expectNoThrow() { exception_expect_ = false; }
42  template <typename T>
43  auto equals(const T v1, const T v2, const T tolerance = std::numeric_limits<T>::epsilon()) const
44  -> bool
45  {
46  if (std::abs(v2 - v1) <= tolerance) {
47  return true;
48  }
49  return false;
50  }
51  void spawnEgoEntity(
52  const traffic_simulator::CanonicalizedLaneletPose & spawn_lanelet_pose,
53  const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_pose,
54  const traffic_simulator_msgs::msg::VehicleParameters & parameters);
55 
56  auto isVehicle(const std::string & name) const -> bool;
57 
58  auto isPedestrian(const std::string & name) const -> bool;
59 
60 protected:
63 
64 private:
65  std::string scenario_filename_;
66  std::string ego_model_;
67  bool exception_expect_;
68  std::string junit_path_;
69  void update();
70  virtual void onUpdate() = 0;
71  virtual void onInitialize() = 0;
72  rclcpp::TimerBase::SharedPtr update_timer_;
73  int timeout_;
74  auto configure(
75  std::string map_path, const std::string & lanelet2_map_file,
76  const std::string & scenario_filename, const bool verbose,
77  const std::set<std::uint8_t> & auto_sink_entity_types = {}) -> traffic_simulator::Configuration
78  {
80  if (map_path.empty()) {
81  declare_parameter<std::string>("map_path", "");
82  get_parameter<std::string>("map_path", map_path);
83  }
84 
85  auto configuration = traffic_simulator::Configuration(
86  map_path, lanelet2_map_file, scenario_filename, auto_sink_entity_types);
87  configuration.verbose = verbose;
88  checkConfiguration(configuration);
89  return configuration;
90  }
91 
92  void checkConfiguration(const traffic_simulator::Configuration & configuration);
93 };
94 
95 } // namespace cpp_mock_scenarios
96 
97 #endif // CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
Definition: cpp_scenario_node.hpp:31
void expectThrow()
Definition: cpp_scenario_node.hpp:40
void spawnEgoEntity(const traffic_simulator::CanonicalizedLaneletPose &spawn_lanelet_pose, const std::vector< traffic_simulator::CanonicalizedLaneletPose > &goal_lanelet_pose, const traffic_simulator_msgs::msg::VehicleParameters &parameters)
Definition: cpp_scenario_node.cpp:107
auto isPedestrian(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:158
traffic_simulator::API api_
Definition: cpp_scenario_node.hpp:61
void start(const bool start_scenario_clock=true)
Definition: cpp_scenario_node.cpp:67
auto isVehicle(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:152
common::junit::JUnit5 junit_
Definition: cpp_scenario_node.hpp:62
CppScenarioNode(const std::string &node_name, const std::string &map_path, const std::string &lanelet2_map_file, const std::string &scenario_filename, const bool verbose, const rclcpp::NodeOptions &option, const std::set< std::uint8_t > &auto_sink_entity_types={})
Definition: cpp_scenario_node.cpp:20
void expectNoThrow()
Definition: cpp_scenario_node.hpp:41
void stop(Result result, const std::string &description="")
Definition: cpp_scenario_node.cpp:80
auto equals(const T v1, const T v2, const T tolerance=std::numeric_limits< T >::epsilon()) const -> bool
Definition: cpp_scenario_node.hpp:43
Definition: api.hpp:56
Definition: lanelet_pose.hpp:28
Definition: cpp_scenario_node.hpp:27
Result
Definition: cpp_scenario_node.hpp:28
std::string string
Definition: junit5.hpp:26
Definition: junit5.hpp:336
Definition: configuration.hpp:31