15 #ifndef TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
18 #include <tf2/LinearMath/Quaternion.h>
19 #include <tf2_ros/static_transform_broadcaster.h>
20 #include <tf2_ros/transform_broadcaster.h>
24 #include <rclcpp/node_interfaces/get_node_topics_interface.hpp>
25 #include <rclcpp/node_interfaces/node_topics_interface.hpp>
26 #include <rclcpp/rclcpp.hpp>
30 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
46 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
47 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
48 #include <traffic_simulator_msgs/msg/entity_status_with_trajectory_array.hpp>
49 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
50 #include <type_traits>
51 #include <unordered_map>
54 #include <visualization_msgs/msg/marker_array.hpp>
63 explicit LaneletMarkerQoS(std::size_t depth = 1) : rclcpp::QoS(depth) { transient_local(); }
76 std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> node_topics_interface;
77 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
79 tf2_ros::StaticTransformBroadcaster broadcaster_;
80 tf2_ros::TransformBroadcaster base_link_broadcaster_;
82 const rclcpp::Clock::SharedPtr clock_ptr_;
84 std::unordered_map<std::string, std::shared_ptr<traffic_simulator::entity::EntityBase>> entities_;
86 bool npc_logic_started_;
88 using EntityStatusWithTrajectoryArray =
89 traffic_simulator_msgs::msg::EntityStatusWithTrajectoryArray;
90 const rclcpp::Publisher<EntityStatusWithTrajectoryArray>::SharedPtr entity_status_array_pub_ptr_;
92 using MarkerArray = visualization_msgs::msg::MarkerArray;
93 const rclcpp::Publisher<MarkerArray>::SharedPtr lanelet_marker_pub_ptr_;
95 const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_ptr_;
97 MarkerArray markers_raw_;
99 std::shared_ptr<traffic_simulator::TrafficLights> traffic_lights_ptr_;
108 const std::shared_ptr<traffic_simulator::TrafficLights> & traffic_lights_ptr) ->
void
110 traffic_lights_ptr_ = traffic_lights_ptr;
113 template <
typename Node>
116 geographic_msgs::msg::GeoPoint origin;
118 if (!node.has_parameter(
"origin_latitude")) {
119 node.declare_parameter(
"origin_latitude", 0.0);
121 if (!node.has_parameter(
"origin_longitude")) {
122 node.declare_parameter(
"origin_longitude", 0.0);
124 node.get_parameter(
"origin_latitude", origin.latitude);
125 node.get_parameter(
"origin_longitude", origin.longitude);
131 template <
class NodeT,
class AllocatorT = std::allocator<
void>>
134 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters)
135 : configuration(configuration),
136 node_topics_interface(rclcpp::node_interfaces::get_node_topics_interface(node)),
137 node_parameters_(node_parameters),
139 base_link_broadcaster_(node),
140 clock_ptr_(node->get_clock()),
141 npc_logic_started_(false),
142 entity_status_array_pub_ptr_(rclcpp::create_publisher<EntityStatusWithTrajectoryArray>(
144 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
145 lanelet_marker_pub_ptr_(rclcpp::create_publisher<MarkerArray>(
147 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
149 configuration.lanelet2_map_path(),
getOrigin(*node))),
150 markers_raw_(hdmap_utils_ptr_->generateMarker())
190 ->
std::optional<traffic_simulator_msgs::msg::Obstacle>;
193 -> const traffic_simulator_msgs::msg::PedestrianParameters &;
196 -> const traffic_simulator_msgs::msg::VehicleParameters &;
198 auto
getWaypoints(const
std::
string & name) -> traffic_simulator_msgs::msg::WaypointsArray;
200 template <typename T>
204 if (not npc_logic_started_) {
207 return entities_.at(name)->getGoalPoses();
210 if (not npc_logic_started_) {
213 std::vector<geometry_msgs::msg::Pose> poses;
214 for (
const auto & lanelet_pose : getGoalPoses<CanonicalizedLaneletPose>(name)) {
238 template <typename Entity, typename
Pose, typename Parameters, typename... Ts>
240 const
std::
string & name, const
Pose & pose, const Parameters & parameters,
241 const
double current_time, Ts &&...
xs)
245 std::is_same<Pose, CanonicalizedLaneletPose>,
246 std::is_same<Pose, geometry_msgs::msg::Pose>>::value,
247 "Pose must be of type CanonicalizedLaneletPose or geometry_msgs::msg::Pose");
252 if constexpr (std::is_same_v<std::decay_t<Entity>,
EgoEntity>) {
256 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::EGO;
258 }
else if constexpr (std::is_same_v<std::decay_t<Entity>,
VehicleEntity>) {
259 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::VEHICLE;
260 }
else if constexpr (std::is_same_v<std::decay_t<Entity>,
PedestrianEntity>) {
261 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::PEDESTRIAN;
263 entity_status.type.type = traffic_simulator_msgs::msg::EntityType::MISC_OBJECT;
266 entity_status.subtype = parameters.subtype;
267 entity_status.time = current_time;
268 entity_status.name = name;
269 entity_status.bounding_box = parameters.bounding_box;
270 entity_status.action_status = traffic_simulator_msgs::msg::ActionStatus();
271 entity_status.action_status.current_action =
"waiting for initialize";
273 const auto include_crosswalk = [](
const auto & entity_type) {
274 return (traffic_simulator_msgs::msg::EntityType::PEDESTRIAN == entity_type.type) ||
275 (traffic_simulator_msgs::msg::EntityType::MISC_OBJECT == entity_type.type);
276 }(entity_status.type);
278 const auto matching_distance = [](
const auto & local_parameters) {
279 if constexpr (std::is_same_v<
280 std::decay_t<Parameters>, traffic_simulator_msgs::msg::VehicleParameters>) {
282 local_parameters.axles.front_axle.track_width,
283 local_parameters.axles.rear_axle.track_width) *
287 return local_parameters.bounding_box.dimensions.y * 0.5 + 1.0;
291 if constexpr (std::is_same_v<std::decay_t<Pose>,
LaneletPose>) {
293 "LaneletPose is not supported type as pose argument. Only CanonicalizedLaneletPose and "
294 "msg::Pose are supported as pose argument of EntityManager::spawnEntity().");
299 entity_status.pose = pose;
301 pose, parameters.bounding_box, include_crosswalk, matching_distance);
306 if (
const auto [iter, success] = entities_.emplace(
307 name, std::make_unique<Entity>(
309 std::forward<decltype(
xs)>(
xs)...));
312 iter->second->setTrafficLights(traffic_lights_ptr_->getConventionalTrafficLights());
319 template <
typename MessageT,
typename... Args>
322 return rclcpp::create_publisher<MessageT>(node_topics_interface, std::forward<Args>(args)...);
325 template <
typename MessageT,
typename... Args>
328 return rclcpp::create_subscription<MessageT>(
329 node_topics_interface, std::forward<Args>(args)...);
332 void update(
const double current_time,
const double step_time);
Definition: ego_entity.hpp:35
Definition: entity_base.hpp:51
Definition: entity_manager.hpp:73
auto getGoalPoses(const std::string &name) -> std::vector< T >
Definition: entity_manager.hpp:201
void resetBehaviorPlugin(const std::string &name, const std::string &behavior_plugin_name)
Reset behavior plugin of the target entity. The internal behavior is to take over the various paramet...
Definition: entity_manager.cpp:272
auto createSubscription(Args &&... args)
Definition: entity_manager.hpp:326
void updateHdmapMarker()
Definition: entity_manager.cpp:381
auto isAnyEgoSpawned() const -> bool
Definition: entity_manager.cpp:265
bool despawnEntity(const std::string &name)
Definition: entity_manager.cpp:124
auto getEntityPointer(const std::string &name) const -> std::shared_ptr< traffic_simulator::entity::EntityBase >
Definition: entity_manager.cpp:143
auto getEntityNames() const -> const std::vector< std::string >
Definition: entity_manager.cpp:134
auto getEgoEntity(const std::string &name) -> entity::EgoEntity &
Definition: entity_manager.cpp:178
void setVerbose(const bool verbose)
Definition: entity_manager.cpp:306
auto getFirstEgoName() const -> std::optional< std::string >
Definition: entity_manager.cpp:213
auto getWaypoints(const std::string &name) -> traffic_simulator_msgs::msg::WaypointsArray
Definition: entity_manager.cpp:255
auto isNpcLogicStarted() const -> bool
Definition: entity_manager.hpp:338
auto spawnEntity(const std::string &name, const Pose &pose, const Parameters ¶meters, const double current_time, Ts &&... xs)
Definition: entity_manager.hpp:239
auto setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLights > &traffic_lights_ptr) -> void
Definition: entity_manager.hpp:107
EntityManager(NodeT &&node, const Configuration &configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
Definition: entity_manager.hpp:132
auto isEntityExist(const std::string &name) const -> bool
Definition: entity_manager.cpp:129
auto getHdmapUtils() -> const std::shared_ptr< hdmap_utils::HdMapUtils > &
Definition: entity_manager.cpp:201
auto getPedestrianParameters(const std::string &name) const -> const traffic_simulator_msgs::msg::PedestrianParameters &
Definition: entity_manager.cpp:233
auto getOrigin(Node &node) const
Definition: entity_manager.hpp:114
void broadcastTransform(const geometry_msgs::msg::PoseStamped &pose, const bool static_transform=true)
Definition: entity_manager.cpp:94
void update(const double current_time, const double step_time)
Definition: entity_manager.cpp:331
auto getEntity(const std::string &name) -> entity::EntityBase &
Definition: entity_manager.cpp:160
visualization_msgs::msg::MarkerArray makeDebugMarker() const
Definition: entity_manager.cpp:115
auto createPublisher(Args &&... args)
Definition: entity_manager.hpp:320
auto updateNpcLogic(const std::string &name, const double current_time, const double step_time) -> const CanonicalizedEntityStatus &
Definition: entity_manager.cpp:314
auto getVehicleParameters(const std::string &name) const -> const traffic_simulator_msgs::msg::VehicleParameters &
Definition: entity_manager.cpp:244
auto startNpcLogic(const double current_time) -> void
Definition: entity_manager.cpp:393
auto getObstacle(const std::string &name) -> std::optional< traffic_simulator_msgs::msg::Obstacle >
Definition: entity_manager.cpp:223
auto getNumberOfEgo() const -> std::size_t
Definition: entity_manager.cpp:206
void broadcastEntityTransform()
Definition: entity_manager.cpp:40
Definition: entity_manager.hpp:67
EntityMarkerQoS(std::size_t depth=100)
Definition: entity_manager.hpp:69
Definition: entity_manager.hpp:61
LaneletMarkerQoS(std::size_t depth=1)
Definition: entity_manager.hpp:63
Definition: pedestrian_entity.hpp:34
Definition: vehicle_entity.hpp:37
Definition: entity_status.hpp:32
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:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:66
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::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: configuration.hpp:31
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:115