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  void start();
38  void stop(Result result, const std::string & description = "");
39  void expectThrow() { exception_expect_ = true; }
40  void expectNoThrow() { exception_expect_ = false; }
41  template <typename T>
42  auto equals(const T v1, const T v2, const T tolerance = std::numeric_limits<T>::epsilon()) const
43  -> bool
44  {
45  if (std::abs(v2 - v1) <= tolerance) {
46  return true;
47  }
48  return false;
49  }
50  void spawnEgoEntity(
51  const traffic_simulator::CanonicalizedLaneletPose & spawn_lanelet_pose,
52  const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_pose,
53  const traffic_simulator_msgs::msg::VehicleParameters & parameters);
54 
55  auto isVehicle(const std::string & name) const -> bool;
56 
57  auto isPedestrian(const std::string & name) const -> bool;
58 
59 protected:
62 
63 private:
64  std::string scenario_filename_;
65  bool exception_expect_;
66  std::string junit_path_;
67  void update();
68  virtual void onUpdate() = 0;
69  virtual void onInitialize() = 0;
70  rclcpp::TimerBase::SharedPtr update_timer_;
71  int timeout_;
72  auto configure(
73  const std::string & map_path, const std::string & lanelet2_map_file,
74  const std::string & scenario_filename, const bool verbose) -> traffic_simulator::Configuration
75  {
76  auto configuration = traffic_simulator::Configuration(map_path);
77  {
78  configuration.lanelet2_map_file = lanelet2_map_file;
79  // configuration.lanelet2_map_file = "lanelet2_map_with_private_road_and_walkway_ele_fix.osm";
80  configuration.scenario_path = scenario_filename;
81  configuration.verbose = verbose;
82  }
83  checkConfiguration(configuration);
84  return configuration;
85  }
86 
87  void checkConfiguration(const traffic_simulator::Configuration & configuration);
88 };
89 
90 } // namespace cpp_mock_scenarios
91 
92 #endif // CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
Definition: cpp_scenario_node.hpp:31
void expectThrow()
Definition: cpp_scenario_node.hpp:39
void start()
Definition: cpp_scenario_node.cpp:63
auto isPedestrian(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:144
traffic_simulator::API api_
Definition: cpp_scenario_node.hpp:60
auto isVehicle(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:138
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:99
common::junit::JUnit5 junit_
Definition: cpp_scenario_node.hpp:61
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)
Definition: cpp_scenario_node.cpp:20
void expectNoThrow()
Definition: cpp_scenario_node.hpp:40
void stop(Result result, const std::string &description="")
Definition: cpp_scenario_node.cpp:72
auto equals(const T v1, const T v2, const T tolerance=std::numeric_limits< T >::epsilon()) const -> bool
Definition: cpp_scenario_node.hpp:42
Definition: api.hpp:64
Definition: lanelet_pose.hpp:27
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:29