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>
35 #include <vector>
36 
37 namespace traffic_simulator
38 {
39 namespace traffic
40 {
42 {
43 public:
44  explicit TrafficSink(
45  lanelet::Id lanelet_id, double radius, const geometry_msgs::msg::Point & position,
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);
49  const lanelet::Id lanelet_id;
50  const double radius;
51  const geometry_msgs::msg::Point position;
52  void execute(const double current_time, const double step_time) override;
53  auto appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const
54  -> void override;
55 
56 private:
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;
60 };
61 } // namespace traffic
62 } // namespace traffic_simulator
63 
64 #endif // TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_
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
Definition: api.hpp:49
std::string string
Definition: junit5.hpp:26