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);
42 auto equals(
const T v1,
const T v2,
const T tolerance = std::numeric_limits<T>::epsilon()) const
45 if (std::abs(v2 - v1) <= tolerance) {
52 const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_pose,
53 const traffic_simulator_msgs::msg::VehicleParameters & parameters);
65 bool exception_expect_;
68 virtual void onUpdate() = 0;
69 virtual void onInitialize() = 0;
70 rclcpp::TimerBase::SharedPtr update_timer_;
78 configuration.lanelet2_map_file = lanelet2_map_file;
80 configuration.scenario_path = scenario_filename;
81 configuration.verbose = verbose;
83 checkConfiguration(configuration);
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 ¶meters)
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: 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