15 #ifndef CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
16 #define CPP_MOCK_SCENARIOS__CPP_SCENARIO_NODE_HPP_
20 #include <rclcpp/rclcpp.hpp>
36 const bool verbose,
const rclcpp::NodeOptions & option,
37 const std::set<std::uint8_t> & auto_sink_entity_types = {});
43 auto equals(
const T v1,
const T v2,
const T tolerance = std::numeric_limits<T>::epsilon()) const
46 if (std::abs(v2 - v1) <= tolerance) {
53 const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_pose,
54 const traffic_simulator_msgs::msg::VehicleParameters & parameters);
66 bool exception_expect_;
69 virtual void onUpdate() = 0;
70 virtual void onInitialize() = 0;
71 rclcpp::TimerBase::SharedPtr update_timer_;
75 const std::string & scenario_filename,
const bool verbose,
80 configuration.lanelet2_map_file = lanelet2_map_file;
82 configuration.scenario_path = scenario_filename;
83 configuration.verbose = verbose;
84 configuration.auto_sink_entity_types = auto_sink_entity_types;
86 checkConfiguration(configuration);
Definition: cpp_scenario_node.hpp:31
void expectThrow()
Definition: cpp_scenario_node.hpp:40
void start()
Definition: cpp_scenario_node.cpp:65
auto isPedestrian(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:146
traffic_simulator::API api_
Definition: cpp_scenario_node.hpp:61
auto isVehicle(const std::string &name) const -> bool
Definition: cpp_scenario_node.cpp:140
void spawnEgoEntity(const traffic_simulator::CanonicalizedLaneletPose &spawn_lanelet_pose, const std::vector< traffic_simulator::CanonicalizedLaneletPose > &goal_lanelet_pose, const traffic_simulator_msgs::msg::VehicleParameters ¶meters)
Definition: cpp_scenario_node.cpp:101
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:74
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: 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:30