26 #ifndef TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
27 #define TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
29 #include <lanelet2_core/geometry/Lanelet.h>
32 #include <geometry_msgs/msg/pose.hpp>
46 const std::function<std::vector<std::string>(
void)> & get_entity_names_function,
47 const std::function<geometry_msgs::msg::Pose(
const std::string &)> & get_entity_pose_function,
48 const std::function<
void(
std::string)> & despawn_function);
52 void execute(
const double current_time,
const double step_time)
override;
57 const std::function<std::vector<std::string>(
void)> get_entity_names_function;
58 const std::function<geometry_msgs::msg::Pose(
const std::string &)> get_entity_pose_function;
59 const std::function<void(
const std::string &)> despawn_function;
Definition: traffic_module_base.hpp:36
Definition: traffic_sink.hpp:42
TrafficSink(lanelet::Id lanelet_id, double radius, const geometry_msgs::msg::Point &position, const std::function< std::vector< std::string >(void)> &get_entity_names_function, const std::function< geometry_msgs::msg::Pose(const std::string &)> &get_entity_pose_function, const std::function< void(std::string)> &despawn_function)
Definition: traffic_sink.cpp:40
auto appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) const -> void override
Definition: traffic_sink.cpp:67
void execute(const double current_time, const double step_time) override
Definition: traffic_sink.cpp:55
const lanelet::Id lanelet_id
Definition: traffic_sink.hpp:49
const geometry_msgs::msg::Point position
Definition: traffic_sink.hpp:51
const double radius
Definition: traffic_sink.hpp:50
std::string string
Definition: junit5.hpp:26