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>
54 const std::optional<lanelet::Id> lanelet_id_opt)
59 static long unique_id = 0L;
60 if (lanelet_id_opt.has_value()) {
84 const std::shared_ptr<entity::EntityManager> entity_manager_ptr,
91 auto execute(
const double current_time,
const double step_time) ->
void override;
92 auto appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array)
const
96 auto isEntitySinkable(
const std::string & entity_name)
const noexcept(
false) -> bool;
99 const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
Definition: traffic_module_base.hpp:36
Definition: traffic_sink.hpp:76
auto execute(const std::vector< std::string > &) -> int
Definition: execute.cpp:36
char const * to_string(const RoutingGraphType &)
Definition: routing_graph_type.cpp:21
std::string string
Definition: junit5.hpp:26
Definition: traffic_sink.hpp:44
const double radius
Definition: traffic_sink.hpp:69
const std::set< std::uint8_t > sinkable_entity_types
Definition: traffic_sink.hpp:71
TrafficSinkConfig(const double radius, const geometry_msgs::msg::Point &position, const std::set< std::uint8_t > &sinkable_entity_types, const std::optional< lanelet::Id > lanelet_id_opt)
Construct a new TrafficSinkConfig object.
Definition: traffic_sink.hpp:51
const geometry_msgs::msg::Point position
Definition: traffic_sink.hpp:70
const std::string description
Definition: traffic_sink.hpp:72