scenario_simulator_v2 C++ API
traffic_sink.hpp
Go to the documentation of this file.
1 
12 // Copyright 2015 TIER IV.inc. All rights reserved.
13 //
14 // Licensed under the Apache License, Version 2.0 (the "License");
15 // you may not use this file except in compliance with the License.
16 // You may obtain a copy of the License at
17 //
18 // http://www.apache.org/licenses/LICENSE-2.0
19 //
20 // Unless required by applicable law or agreed to in writing, software
21 // distributed under the License is distributed on an "AS IS" BASIS,
22 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 // See the License for the specific language governing permissions and
24 // limitations under the License.
25 
26 #ifndef TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
27 #define TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
28 
29 #include <lanelet2_core/geometry/Lanelet.h>
30 
31 #include <functional>
32 #include <geometry_msgs/msg/pose.hpp>
33 #include <string>
37 #include <vector>
38 
39 namespace traffic_simulator
40 {
41 namespace traffic
42 {
44 {
52  const double radius, const geometry_msgs::msg::Point & position,
53  const std::set<std::uint8_t> & sinkable_entity_types,
54  const std::optional<lanelet::Id> lanelet_id_opt)
55  : radius(radius),
58  description([](const std::optional<lanelet::Id> lanelet_id_opt) -> std::string {
59  static long unique_id = 0L;
60  if (lanelet_id_opt.has_value()) {
61  return std::string("auto_") + std::to_string(lanelet_id_opt.value());
62  } else {
63  return std::string("custom_") + std::to_string(unique_id++);
64  }
65  }(lanelet_id_opt))
66  {
67  }
68 
69  const double radius;
70  const geometry_msgs::msg::Point position;
71  const std::set<std::uint8_t> sinkable_entity_types;
73 };
74 
76 {
77 public:
83  explicit TrafficSink(
84  const std::shared_ptr<entity::EntityManager> entity_manager_ptr,
85  const TrafficSinkConfig & config);
91  auto execute(const double current_time, const double step_time) -> void override;
92  auto appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const
93  -> void override;
94 
95 private:
96  auto isEntitySinkable(const std::string & entity_name) const noexcept(false) -> bool;
97 
98  const TrafficSinkConfig config_;
99  const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
100 };
101 } // namespace traffic
102 } // namespace traffic_simulator
103 
104 #endif // TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
Definition: traffic_module_base.hpp:36
Definition: traffic_sink.hpp:76
auto execute(const std::vector< std::string > &) -> int
Definition: execute.cpp:36
Definition: cache.hpp:27
char const * to_string(const RoutingGraphType &)
Definition: routing_graph_type.cpp:21
Definition: api.hpp:48
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