Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add despawn_function argument #1502

Merged
merged 7 commits into from
Jan 10, 2025
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,8 @@ class API
node, entity_manager_ptr_->getHdmapUtils(),
getROS2Parameter<std::string>("architecture_type", "awf/universe/20240605"))),
traffic_controller_ptr_(std::make_shared<traffic::TrafficController>(
entity_manager_ptr_, configuration.auto_sink_entity_types)),
[this](const std::string & name) { despawn(name); }, entity_manager_ptr_,
configuration.auto_sink_entity_types)),
clock_pub_(rclcpp::create_publisher<rosgraph_msgs::msg::Clock>(
node, "/clock", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ class TrafficController
{
public:
explicit TrafficController(
const std::function<void(const std::string &)> & despawn_,
const std::shared_ptr<entity::EntityManager> entity_manager_ptr,
const std::set<std::uint8_t> auto_sink_entity_types /*= {}*/);

Expand All @@ -57,6 +58,7 @@ class TrafficController

private:
auto appendAutoSinks(const std::set<std::uint8_t> & auto_sink_entity_types) -> void;
const std::function<void(const std::string &)> despawn_;
const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
std::vector<std::shared_ptr<TrafficModuleBase>> modules_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ class TrafficSink : public TrafficModuleBase
* @param config TrafficSink configuration
*/
explicit TrafficSink(
const std::function<void(const std::string &)> & despawn_function,
const std::shared_ptr<entity::EntityManager> entity_manager_ptr,
const TrafficSinkConfig & config);
/**
Expand All @@ -95,8 +96,9 @@ class TrafficSink : public TrafficModuleBase
private:
auto isEntitySinkable(const std::string & entity_name) const noexcept(false) -> bool;

const TrafficSinkConfig config_;
const std::function<void(const std::string &)> despawn_;
const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
const TrafficSinkConfig config_;
};
} // namespace traffic
} // namespace traffic_simulator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,10 @@ namespace traffic_simulator
namespace traffic
{
TrafficController::TrafficController(
const std::function<void(const std::string &)> & despawn,
const std::shared_ptr<entity::EntityManager> entity_manager_ptr,
const std::set<std::uint8_t> auto_sink_entity_types)
: entity_manager_ptr_(entity_manager_ptr), modules_()
: despawn_(despawn), entity_manager_ptr_(entity_manager_ptr), modules_()
{
if (not auto_sink_entity_types.empty()) {
appendAutoSinks(auto_sink_entity_types);
Expand All @@ -59,7 +60,7 @@ auto TrafficController::appendAutoSinks(const std::set<std::uint8_t> & auto_sink
const auto pose = pose::toMapPose(lanelet_pose, hdmap_utils_ptr);
const auto traffic_sink_config = TrafficSinkConfig(
sink_radius, pose.position, auto_sink_entity_types, std::make_optional(lanelet_id));
addModule<TrafficSink>(entity_manager_ptr_, traffic_sink_config);
addModule<TrafficSink>(despawn_, entity_manager_ptr_, traffic_sink_config);
}
}
}
Expand Down
5 changes: 3 additions & 2 deletions simulation/traffic_simulator/src/traffic/traffic_sink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@ namespace traffic_simulator
namespace traffic
{
TrafficSink::TrafficSink(
const std::function<void(const std::string &)> & despawn,
const std::shared_ptr<entity::EntityManager> entity_manager_ptr, const TrafficSinkConfig & config)
: TrafficModuleBase(), config_(config), entity_manager_ptr_(entity_manager_ptr)
: TrafficModuleBase(), despawn_(despawn), entity_manager_ptr_(entity_manager_ptr), config_(config)
{
}

Expand All @@ -50,7 +51,7 @@ auto TrafficSink::execute(
{
for (const auto & entity_name : entity_manager_ptr_->getEntityNames()) {
if (isEntitySinkable(entity_name)) {
entity_manager_ptr_->despawnEntity(entity_name);
despawn_(entity_name);
}
}
}
Expand Down
Loading