26 #ifndef TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_CONTROLLER_HPP_
27 #define TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_CONTROLLER_HPP_
45 std::shared_ptr<hdmap_utils::HdMapUtils>
hdmap_utils,
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,
50 template <
typename T,
typename... Ts>
53 auto module_ptr = std::make_shared<T>(std::forward<Ts>(
xs)...);
54 modules_.emplace_back(module_ptr);
56 void execute(
const double current_time,
const double step_time);
57 auto makeDebugMarker() const -> const visualization_msgs::msg::MarkerArray;
63 const
std::function<
std::vector<
std::
string>(
void)> get_entity_names_function;
64 const
std::function<geometry_msgs::msg::Pose(const
std::
string &)> get_entity_pose_function;
65 const
std::function<
void(const
std::
string &)> despawn_function;
Definition: traffic_controller.hpp:42
const bool auto_sink
Definition: traffic_controller.hpp:68
TrafficController(std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils, 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, bool auto_sink=false)
Definition: traffic_controller.cpp:39
void addModule(Ts &&... xs)
Definition: traffic_controller.hpp:51
auto makeDebugMarker() const -> const visualization_msgs::msg::MarkerArray
Definition: traffic_controller.cpp:77
void execute(const double current_time, const double step_time)
Definition: traffic_controller.cpp:70
Definition: traffic_module_base.hpp:36
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26