scenario_simulator_v2 C++ API
entity_manager.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
17 
18 #include <tf2/LinearMath/Quaternion.h>
19 #include <tf2_ros/static_transform_broadcaster.h>
20 #include <tf2_ros/transform_broadcaster.h>
21 
22 #include <memory>
23 #include <optional>
24 #include <rclcpp/node_interfaces/get_node_topics_interface.hpp>
25 #include <rclcpp/node_interfaces/node_topics_interface.hpp>
26 #include <rclcpp/rclcpp.hpp>
28 #include <stdexcept>
29 #include <string>
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>
52 #include <utility>
53 #include <vector>
54 #include <visualization_msgs/msg/marker_array.hpp>
55 
56 namespace traffic_simulator
57 {
58 namespace entity
59 {
60 class LaneletMarkerQoS : public rclcpp::QoS
61 {
62 public:
63  explicit LaneletMarkerQoS(std::size_t depth = 1) : rclcpp::QoS(depth) { transient_local(); }
64 };
65 
66 class EntityMarkerQoS : public rclcpp::QoS
67 {
68 public:
69  explicit EntityMarkerQoS(std::size_t depth = 100) : rclcpp::QoS(depth) {}
70 };
71 
73 {
74  Configuration configuration;
75 
76  std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> node_topics_interface;
77  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
78 
79  tf2_ros::StaticTransformBroadcaster broadcaster_;
80  tf2_ros::TransformBroadcaster base_link_broadcaster_;
81 
82  const rclcpp::Clock::SharedPtr clock_ptr_;
83 
84  std::unordered_map<std::string, std::shared_ptr<traffic_simulator::entity::EntityBase>> entities_;
85 
86  bool npc_logic_started_;
87 
88  using EntityStatusWithTrajectoryArray =
89  traffic_simulator_msgs::msg::EntityStatusWithTrajectoryArray;
90  const rclcpp::Publisher<EntityStatusWithTrajectoryArray>::SharedPtr entity_status_array_pub_ptr_;
91 
92  using MarkerArray = visualization_msgs::msg::MarkerArray;
93  const rclcpp::Publisher<MarkerArray>::SharedPtr lanelet_marker_pub_ptr_;
94 
95  const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_ptr_;
96 
97  MarkerArray markers_raw_;
98 
99  std::shared_ptr<traffic_simulator::TrafficLights> traffic_lights_ptr_;
100 
101 public:
108  const std::shared_ptr<traffic_simulator::TrafficLights> & traffic_lights_ptr) -> void
109  {
110  traffic_lights_ptr_ = traffic_lights_ptr;
111  }
112 
113  template <typename Node>
114  auto getOrigin(Node & node) const
115  {
116  geographic_msgs::msg::GeoPoint origin;
117  {
118  if (!node.has_parameter("origin_latitude")) {
119  node.declare_parameter("origin_latitude", 0.0);
120  }
121  if (!node.has_parameter("origin_longitude")) {
122  node.declare_parameter("origin_longitude", 0.0);
123  }
124  node.get_parameter("origin_latitude", origin.latitude);
125  node.get_parameter("origin_longitude", origin.longitude);
126  }
127 
128  return origin;
129  }
130 
131  template <class NodeT, class AllocatorT = std::allocator<void>>
132  explicit EntityManager(
133  NodeT && node, const Configuration & configuration,
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),
138  broadcaster_(node),
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>(
143  node, "entity/status", EntityMarkerQoS(),
144  rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
145  lanelet_marker_pub_ptr_(rclcpp::create_publisher<MarkerArray>(
146  node, "lanelet/marker", LaneletMarkerQoS(),
147  rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
148  hdmap_utils_ptr_(std::make_shared<hdmap_utils::HdMapUtils>(
149  configuration.lanelet2_map_path(), getOrigin(*node))),
150  markers_raw_(hdmap_utils_ptr_->generateMarker())
151  {
153  }
154 
155  ~EntityManager() = default;
156 
157 public:
158  visualization_msgs::msg::MarkerArray makeDebugMarker() const;
159 
160  auto updateNpcLogic(const std::string & name, const double current_time, const double step_time)
161  -> const CanonicalizedEntityStatus &;
162 
164 
165  void broadcastTransform(
166  const geometry_msgs::msg::PoseStamped & pose, const bool static_transform = true);
167 
168  bool despawnEntity(const std::string & name);
169 
170  auto isEntityExist(const std::string & name) const -> bool;
171 
172  auto getEntityNames() const -> const std::vector<std::string>;
173 
174  auto getEntityPointer(const std::string & name) const
175  -> std::shared_ptr<traffic_simulator::entity::EntityBase>;
176 
177  auto getEntity(const std::string & name) -> entity::EntityBase &;
178 
179  auto getEntity(const std::string & name) const -> const entity::EntityBase &;
180 
181  auto getEgoEntity(const std::string & name) -> entity::EgoEntity &;
182 
183  auto getEgoEntity(const std::string & name) const -> const entity::EgoEntity &;
184 
185  auto getHdmapUtils() -> const std::shared_ptr<hdmap_utils::HdMapUtils> &;
186 
187  auto getNumberOfEgo() const -> std::size_t;
188 
189  auto getObstacle(const std::string & name)
190  -> std::optional<traffic_simulator_msgs::msg::Obstacle>;
191 
192  auto getPedestrianParameters(const std::string & name) const
193  -> const traffic_simulator_msgs::msg::PedestrianParameters &;
194 
195  auto getVehicleParameters(const std::string & name) const
196  -> const traffic_simulator_msgs::msg::VehicleParameters &;
197 
198  auto getWaypoints(const std::string & name) -> traffic_simulator_msgs::msg::WaypointsArray;
199 
200  template <typename T>
201  auto getGoalPoses(const std::string & name) -> std::vector<T>
202  {
203  if constexpr (std::is_same_v<std::decay_t<T>, CanonicalizedLaneletPose>) {
204  if (not npc_logic_started_) {
205  return {};
206  } else {
207  return entities_.at(name)->getGoalPoses();
208  }
209  } else {
210  if (not npc_logic_started_) {
211  return {};
212  } else {
213  std::vector<geometry_msgs::msg::Pose> poses;
214  for (const auto & lanelet_pose : getGoalPoses<CanonicalizedLaneletPose>(name)) {
215  poses.push_back(pose::toMapPose(lanelet_pose));
216  }
217  return poses;
218  }
219  }
220  }
221 
222  auto isAnyEgoSpawned() const -> bool;
223 
224  auto getFirstEgoName() const -> std::optional<std::string>;
225 
234  void resetBehaviorPlugin(const std::string & name, const std::string & behavior_plugin_name);
235 
236  void setVerbose(const bool verbose);
237 
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)
242  {
243  static_assert(
244  std::disjunction<
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");
248 
250  EntityStatus entity_status;
251 
252  if constexpr (std::is_same_v<std::decay_t<Entity>, EgoEntity>) {
253  if (isAnyEgoSpawned()) {
254  THROW_SEMANTIC_ERROR("multi ego simulation does not support yet");
255  } else {
256  entity_status.type.type = traffic_simulator_msgs::msg::EntityType::EGO;
257  }
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;
262  } else {
263  entity_status.type.type = traffic_simulator_msgs::msg::EntityType::MISC_OBJECT;
264  }
265 
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";
272 
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);
277 
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>) {
281  return std::max(
282  local_parameters.axles.front_axle.track_width,
283  local_parameters.axles.rear_axle.track_width) *
284  0.5 +
285  1.0;
286  } else {
287  return local_parameters.bounding_box.dimensions.y * 0.5 + 1.0;
288  }
289  }(parameters);
290 
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().");
295  } else if constexpr (std::is_same_v<std::decay_t<Pose>, CanonicalizedLaneletPose>) {
296  entity_status.pose = pose::toMapPose(pose);
297  return CanonicalizedEntityStatus(entity_status, pose);
298  } else if constexpr (std::is_same_v<std::decay_t<Pose>, geometry_msgs::msg::Pose>) {
299  entity_status.pose = pose;
300  const auto canonicalized_lanelet_pose = pose::toCanonicalizedLaneletPose(
301  pose, parameters.bounding_box, include_crosswalk, matching_distance);
302  return CanonicalizedEntityStatus(entity_status, canonicalized_lanelet_pose);
303  }
304  };
305 
306  if (const auto [iter, success] = entities_.emplace(
307  name, std::make_unique<Entity>(
308  name, makeEntityStatus(), hdmap_utils_ptr_, parameters,
309  std::forward<decltype(xs)>(xs)...));
310  success) {
311  // FIXME: this ignores V2I traffic lights
312  iter->second->setTrafficLights(traffic_lights_ptr_->getConventionalTrafficLights());
313  return success;
314  } else {
315  THROW_SEMANTIC_ERROR("Entity ", std::quoted(name), " is already exists.");
316  }
317  }
318 
319  template <typename MessageT, typename... Args>
320  auto createPublisher(Args &&... args)
321  {
322  return rclcpp::create_publisher<MessageT>(node_topics_interface, std::forward<Args>(args)...);
323  }
324 
325  template <typename MessageT, typename... Args>
326  auto createSubscription(Args &&... args)
327  {
328  return rclcpp::create_subscription<MessageT>(
329  node_topics_interface, std::forward<Args>(args)...);
330  }
331 
332  void update(const double current_time, const double step_time);
333 
334  void updateHdmapMarker();
335 
336  auto startNpcLogic(const double current_time) -> void;
337 
338  auto isNpcLogicStarted() const -> bool { return npc_logic_started_; }
339 };
340 } // namespace entity
341 } // namespace traffic_simulator
342 
343 #endif // TRAFFIC_SIMULATOR__ENTITY__ENTITY_MANAGER_HPP_
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 &parameters, 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: cache.hpp:28
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
Definition: api.hpp:48
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