15 #ifndef TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
18 #include <tf2_ros/static_transform_broadcaster.h>
19 #include <tf2_ros/transform_broadcaster.h>
21 #include <get_parameter/get_parameter.hpp>
33 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
34 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
35 #include <traffic_simulator_msgs/msg/entity_status_with_trajectory_array.hpp>
44 explicit LaneletMarkerQoS(std::size_t depth = 1) : rclcpp::QoS(depth) { transient_local(); }
55 using EntityStatusWithTrajectoryArray =
56 traffic_simulator_msgs::msg::EntityStatusWithTrajectoryArray;
57 using MarkerArray = visualization_msgs::msg::MarkerArray;
60 template <
class NodeT,
class AllocatorT = std::allocator<
void>>
63 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters)
64 : configuration_(configuration),
65 clock_ptr_(node->get_clock()),
66 node_parameters_(node_parameters),
68 base_link_broadcaster_(node),
69 entity_status_array_pub_ptr_(rclcpp::create_publisher<EntityStatusWithTrajectoryArray>(
71 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
72 lanelet_marker_pub_ptr_(rclcpp::create_publisher<MarkerArray>(
74 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
89 auto setTrafficLights(
const std::shared_ptr<TrafficLights> & traffic_lights_ptr) -> void;
100 auto
update(const
double current_time, const
double step_time) ->
void;
103 const
std::
string & name, const
double current_time, const
double step_time,
111 const geometry_msgs::msg::
PoseStamped & pose, const
bool static_transform = true) ->
void;
114 template <typename
EntityType, typename PoseType, typename ParametersType, typename... Ts>
116 const
std::
string & name, const PoseType & pose, const ParametersType & parameters,
117 const
double current_time, Ts &&...
xs) -> entity::
EntityBase &
121 std::is_same<PoseType, CanonicalizedLaneletPose>,
122 std::is_same<PoseType, geometry_msgs::msg::Pose>>::value,
123 "Pose must be of type CanonicalizedLaneletPose or geometry_msgs::msg::Pose");
128 if constexpr (std::is_same_v<std::decay_t<EntityType>,
EgoEntity>) {
132 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::EGO;
134 }
else if constexpr (std::is_same_v<std::decay_t<EntityType>,
VehicleEntity>) {
135 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::VEHICLE;
136 }
else if constexpr (std::is_same_v<std::decay_t<EntityType>,
PedestrianEntity>) {
137 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::PEDESTRIAN;
139 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::MISC_OBJECT;
142 entity_status.subtype = parameters.subtype;
143 entity_status.time = current_time;
144 entity_status.name = name;
145 entity_status.bounding_box = parameters.bounding_box;
146 entity_status.action_status = traffic_simulator_msgs::msg::ActionStatus();
147 entity_status.action_status.current_action =
"waiting for initialize";
149 const auto include_crosswalk = [](
const auto & entity_type) {
150 return (traffic_simulator_msgs::msg::EntityType::PEDESTRIAN == entity_type.type) ||
151 (traffic_simulator_msgs::msg::EntityType::MISC_OBJECT == entity_type.type);
152 }(entity_status.type);
154 const auto matching_distance = [](
const auto & local_parameters) {
155 if constexpr (std::is_same_v<
156 std::decay_t<ParametersType>,
157 traffic_simulator_msgs::msg::VehicleParameters>) {
159 local_parameters.axles.front_axle.track_width,
160 local_parameters.axles.rear_axle.track_width) *
164 return local_parameters.bounding_box.dimensions.y * 0.5 + 1.0;
168 if constexpr (std::is_same_v<std::decay_t<PoseType>,
LaneletPose>) {
170 "LaneletPose is not supported type as pose argument. Only CanonicalizedLaneletPose and "
171 "msg::Pose are supported as pose argument of EntityManager::spawnEntity().");
176 entity_status.pose = pose;
178 pose, parameters.bounding_box, include_crosswalk, matching_distance);
183 if (
const auto [iter, success] = entities_.emplace(
184 name, std::make_unique<EntityType>(
188 iter->second->setTrafficLights(traffic_lights_ptr_->getConventionalTrafficLights());
189 return *(iter->second);
238 const rclcpp::Clock::SharedPtr clock_ptr_;
240 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
242 tf2_ros::StaticTransformBroadcaster broadcaster_;
244 tf2_ros::TransformBroadcaster base_link_broadcaster_;
246 const rclcpp::Publisher<EntityStatusWithTrajectoryArray>::SharedPtr entity_status_array_pub_ptr_;
248 const rclcpp::Publisher<MarkerArray>::SharedPtr lanelet_marker_pub_ptr_;
252 bool npc_logic_started_{
false};
254 std::shared_ptr<TrafficLights> traffic_lights_ptr_{
nullptr};
256 MarkerArray markers_raw_;
Definition: ego_entity.hpp:35
Definition: entity_base.hpp:52
Definition: entity_manager.hpp:54
auto update(const double current_time, const double step_time) -> void
Definition: entity_manager.cpp:65
auto calculateEuclideanDistances() -> std::shared_ptr< EuclideanDistancesMap >
Definition: entity_manager.cpp:365
auto isAnyEgoSpawned() const -> bool
Definition: entity_manager.cpp:235
auto despawnEntity(const std::string &name) -> bool
Definition: entity_manager.cpp:360
auto getEntityNames() const -> const std::vector< std::string >
Definition: entity_manager.cpp:281
auto getEgoEntity(const std::string &name) -> entity::EgoEntity &
Definition: entity_manager.cpp:252
auto resetBehaviorPlugin(const std::string &name, const std::string &behavior_plugin_name) -> void
Reset behavior plugin of the target entity. The internal behavior is to take over the various paramet...
Definition: entity_manager.cpp:326
auto updateLaneletMarker() const -> void
Definition: entity_manager.cpp:140
auto spawnEntity(const std::string &name, const PoseType &pose, const ParametersType ¶meters, const double current_time, Ts &&... xs) -> entity::EntityBase &
Definition: entity_manager.hpp:115
auto getFirstEgoName() const -> std::optional< std::string >
Definition: entity_manager.cpp:242
auto isNpcLogicStarted() const -> bool
Definition: entity_manager.cpp:53
auto broadcastTransform(const geometry_msgs::msg::PoseStamped &pose, const bool static_transform=true) -> void
Definition: entity_manager.cpp:206
EntityManager(NodeT &&node, const Configuration &configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
Definition: entity_manager.hpp:61
auto isEntityExist(const std::string &name) const -> bool
Definition: entity_manager.cpp:276
auto updateNpcLogic(const std::string &name, const double current_time, const double step_time, const std::shared_ptr< EuclideanDistancesMap > &distances) -> const CanonicalizedEntityStatus &
Definition: entity_manager.cpp:122
auto broadcastEntityTransform() -> void
Definition: entity_manager.cpp:152
auto setTrafficLights(const std::shared_ptr< TrafficLights > &traffic_lights_ptr) -> void
Definition: entity_manager.cpp:30
auto getEntity(const std::string &name) -> entity::EntityBase &
Definition: entity_manager.cpp:290
auto makeDebugMarker() const -> visualization_msgs::msg::MarkerArray
Definition: entity_manager.cpp:55
auto setVerbose(const bool verbose) -> void
Definition: entity_manager.cpp:36
auto startNpcLogic(const double current_time) -> void
Definition: entity_manager.cpp:44
auto getNumberOfEgo() const -> std::size_t
Definition: entity_manager.cpp:228
auto getEntityPointer(const std::string &name) const -> std::shared_ptr< entity::EntityBase >
Definition: entity_manager.cpp:308
Definition: entity_manager.hpp:48
EntityMarkerQoS(std::size_t depth=100)
Definition: entity_manager.hpp:50
Definition: entity_manager.hpp:42
LaneletMarkerQoS(std::size_t depth=1)
Definition: entity_manager.hpp:44
Definition: pedestrian_entity.hpp:34
Definition: vehicle_entity.hpp:37
Definition: entity_status.hpp:31
Definition: lanelet_pose.hpp:35
#define THROW_SYNTAX_ERROR(...)
Definition: exception.hpp:62
#define THROW_SEMANTIC_ERROR(...)
Definition: exception.hpp:59
Definition: lanelet_wrapper.hpp:43
std::unordered_map< std::pair< std::string, std::string >, double > EuclideanDistancesMap
Definition: entity_base.hpp:50
auto visualizationMarker() -> visualization_msgs::msg::MarkerArray
Definition: lanelet_map.cpp:60
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:70
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:71
auto toCanonicalizedLaneletPose(const LaneletPose &lanelet_pose) -> std::optional< CanonicalizedLaneletPose >
Definition: pose.cpp:104
auto toMapPose(const CanonicalizedLaneletPose &lanelet_pose) -> geometry_msgs::msg::Pose
Definition: pose.cpp:87
traffic_simulator_msgs::msg::EntityType EntityType
Definition: entity_status.hpp:25
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:24
Definition: junit5.hpp:25
Definition: configuration.hpp:30
auto makeEntityStatus(traffic_simulator::lanelet_pose::CanonicalizedLaneletPose pose, traffic_simulator_msgs::msg::BoundingBox bbox, const double speed=0.0, const std::string name="default_entity_name", const uint8_t type=traffic_simulator_msgs::msg::EntityType::VEHICLE) -> traffic_simulator::EntityStatus
Definition: helper_functions.hpp:104