scenario_simulator_v2 C++ API
api.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__API__API_HPP_
16 #define TRAFFIC_SIMULATOR__API__API_HPP_
17 
18 #include <simulation_interface/simulation_api_schema.pb.h>
19 
22 #include <std_msgs/msg/float64.hpp>
30 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
31 
33 {
35 {
36  static auto autoware() noexcept -> const std::string &
37  {
38  static const std::string name = "Autoware";
39  return name;
40  }
41 };
42 
44 {
45 };
46 
48 {
49  static auto noBehavior() noexcept -> const std::string &
50  {
51  static const std::string name = "";
52  return name;
53  }
54 };
55 
56 class API
57 {
58 public:
59  template <typename NodeT, typename AllocatorT = std::allocator<void>, typename... Ts>
60  explicit API(NodeT && node, const Configuration & configuration, Ts &&... xs)
61  : configuration_(configuration),
62  node_parameters_(
63  rclcpp::node_interfaces::get_node_parameters_interface(std::forward<NodeT>(node))),
64  clock_pub_(rclcpp::create_publisher<rosgraph_msgs::msg::Clock>(
65  node, "/clock", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
66  rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
67  debug_marker_pub_(rclcpp::create_publisher<visualization_msgs::msg::MarkerArray>(
68  node, "debug_marker", rclcpp::QoS(100), rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
69  clock_(
70  common::getParameter<bool>(node_parameters_, "use_sim_time"),
71  std::forward<decltype(xs)>(xs)...),
72  zeromq_client_(
73  simulation_interface::protocol, configuration.simulator_host,
74  common::getParameter<int>(node_parameters_, "port", 5555)),
75  entity_manager_ptr_(
76  std::make_shared<entity::EntityManager>(node, configuration, node_parameters_)),
77  traffic_controller_ptr_(std::make_shared<traffic::TrafficController>(
78  [this](const std::string & name) { despawn(name); }, entity_manager_ptr_,
79  configuration.auto_sink_entity_types)),
80  traffic_lights_ptr_(std::make_shared<TrafficLights>(
81  node, getROS2Parameter<std::string>("architecture_type", "awf/universe/20240605"))),
82  real_time_factor_subscriber_(rclcpp::create_subscription<std_msgs::msg::Float64>(
83  node, "/real_time_factor", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
84  [this](const std_msgs::msg::Float64 & message) {
85  return setSimulationStepTime(message.data);
86  }))
87  {
88  entity_manager_ptr_->setVerbose(configuration_.verbose);
89  entity_manager_ptr_->setTrafficLights(traffic_lights_ptr_);
90  if (not init()) {
91  throw common::SimulationError("Failed to initialize simulator by InitializeRequest");
92  }
93  }
94 
95  // global
96  template <typename ParameterT, typename... Ts>
97  auto getROS2Parameter(Ts &&... xs) const -> decltype(auto)
98  {
99  return common::getParameter<ParameterT>(node_parameters_, std::forward<Ts>(xs)...);
100  }
101 
102  auto init() -> bool;
103 
104  auto setVerbose(const bool verbose) -> void;
105 
106  auto setSimulationStepTime(const double step_time) -> bool;
107 
108  auto startNpcLogic() -> void;
109 
110  auto isNpcLogicStarted() const -> bool;
111 
112  auto getCurrentTime() const noexcept -> double;
113 
114  auto closeZMQConnection() -> void;
115 
116  // update
117  auto updateFrame() -> bool;
118 
119  // entities, ego - spawn
120  template <
121  typename PoseType, typename ParamsType,
122  typename = std::enable_if_t<std::disjunction_v<
123  std::is_same<std::decay_t<ParamsType>, traffic_simulator_msgs::msg::VehicleParameters>,
124  std::is_same<std::decay_t<ParamsType>, traffic_simulator_msgs::msg::PedestrianParameters>,
125  std::is_same<std::decay_t<ParamsType>, traffic_simulator_msgs::msg::MiscObjectParameters>>>>
126  auto spawn(
127  const std::string & name, const PoseType & pose, const ParamsType & parameters,
128  const std::string & behavior = "", const std::string & model3d = "") -> entity::EntityBase &
129  {
130  using VehicleParameters = traffic_simulator_msgs::msg::VehicleParameters;
131  using PedestrianParameters = traffic_simulator_msgs::msg::PedestrianParameters;
132  using MiscObjectParameters = traffic_simulator_msgs::msg::MiscObjectParameters;
133 
134  auto register_to_entity_manager = [&]() -> entity::EntityBase & {
135  if constexpr (std::is_same_v<ParamsType, VehicleParameters>) {
136  if (behavior == VehicleBehavior::autoware()) {
137  return entity_manager_ptr_->spawnEntity<entity::EgoEntity>(
138  name, pose, parameters, getCurrentTime(), configuration_, node_parameters_);
139  } else {
140  return entity_manager_ptr_->spawnEntity<entity::VehicleEntity>(
141  name, pose, parameters, getCurrentTime(),
142  behavior.empty() ? VehicleBehavior::defaultBehavior() : behavior);
143  }
144  } else if constexpr (std::is_same_v<ParamsType, PedestrianParameters>) {
145  return entity_manager_ptr_->spawnEntity<entity::PedestrianEntity>(
146  name, pose, parameters, getCurrentTime(),
147  behavior.empty() ? PedestrianBehavior::defaultBehavior() : behavior);
148  } else if constexpr (std::is_same_v<ParamsType, MiscObjectParameters>) {
149  return entity_manager_ptr_->spawnEntity<entity::MiscObjectEntity>(
150  name, pose, parameters, getCurrentTime());
151  }
152  };
153 
154  auto prepare_and_send_request = [&](const auto & entity, auto & request) -> bool {
155  simulation_interface::toProto(parameters, *request.mutable_parameters());
156  request.mutable_parameters()->set_name(name);
157  request.set_asset_key(model3d);
158  simulation_interface::toProto(entity.getMapPose(), *request.mutable_pose());
159  return zeromq_client_.call(request).result().success();
160  };
161 
162  auto register_to_environment_simulator = [&](const auto & entity) -> bool {
163  if (configuration_.standalone_mode) {
164  return true;
165  } else {
166  if constexpr (std::is_same_v<ParamsType, VehicleParameters>) {
167  simulation_api_schema::SpawnVehicleEntityRequest request;
168  request.set_is_ego(behavior == VehicleBehavior::autoware());
170  request.set_initial_speed(0.0);
171  return prepare_and_send_request(entity, request);
172  } else if constexpr (std::is_same_v<ParamsType, PedestrianParameters>) {
173  simulation_api_schema::SpawnPedestrianEntityRequest request;
174  return prepare_and_send_request(entity, request);
175  } else if constexpr (std::is_same_v<ParamsType, MiscObjectParameters>) {
176  simulation_api_schema::SpawnMiscObjectEntityRequest request;
177  return prepare_and_send_request(entity, request);
178  } else {
179  return false;
180  }
181  }
182  };
183 
184  auto & entity = register_to_entity_manager();
185  if (register_to_environment_simulator(entity)) {
186  return entity;
187  } else {
188  THROW_SEMANTIC_ERROR("Spawn entity ", std::quoted(name), " resulted in failure.");
189  }
190  }
191 
192  // sensors - attach
193  auto attachImuSensor(
194  const std::string &, const simulation_api_schema::ImuSensorConfiguration & configuration)
195  -> bool;
196 
198  const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &) -> bool;
199 
200  auto attachLidarSensor(const simulation_api_schema::LidarConfiguration &) -> bool;
201 
202  auto attachLidarSensor(
203  const std::string &, const double lidar_sensor_delay,
205 
206  auto attachDetectionSensor(const simulation_api_schema::DetectionSensorConfiguration &) -> bool;
207 
209  const std::string &, double detection_sensor_range, bool detect_all_objects_in_range,
210  double pos_noise_stddev, int random_seed, double probability_of_lost,
211  double object_recognition_delay) -> bool;
212 
213  auto attachOccupancyGridSensor(const simulation_api_schema::OccupancyGridSensorConfiguration &)
214  -> bool;
215 
216  // ego - checks, getters
217  auto isAnyEgoSpawned() const -> bool;
218 
219  auto getFirstEgoName() const -> std::optional<std::string>;
220 
221  auto getEgoEntity(const std::string & name) -> entity::EgoEntity &;
222 
223  auto getEgoEntity(const std::string & name) const -> const entity::EgoEntity &;
224 
225  // entities - checks, getters
226  auto isEntityExist(const std::string & name) const -> bool;
227 
228  auto getEntityNames() const -> std::vector<std::string>;
229 
230  auto getEntity(const std::string & name) -> entity::EntityBase &;
231 
232  auto getEntity(const std::string & name) const -> const entity::EntityBase &;
233 
234  auto getEntityPointer(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;
235 
236  // entities - respawn, despawn, reset
237  auto resetBehaviorPlugin(const std::string & name, const std::string & behavior_plugin_name)
238  -> void;
239 
240  auto respawn(
241  const std::string & name, const geometry_msgs::msg::PoseWithCovarianceStamped & new_pose,
242  const geometry_msgs::msg::PoseStamped & goal_pose) -> void;
243 
244  auto despawn(const std::string & name) -> bool;
245 
246  auto despawnEntities() -> bool;
247 
248  // entities - features
249  auto checkCollision(
250  const std::string & first_entity_name, const std::string & second_entity_name) const -> bool;
251 
252  // traffics, lanelet
253  auto getV2ITrafficLights() const -> std::shared_ptr<V2ITrafficLights>;
254 
255  auto getConventionalTrafficLights() const -> std::shared_ptr<ConventionalTrafficLights>;
256 
257  auto getV2IDetectedTrafficLights() const -> std::shared_ptr<DetectedTrafficLights>;
258 
260 
261  auto setTrafficSignalV2IFeature(const lanelet::Id lanelet_id, const bool enabled) -> void;
262 
263  auto isV2ITrafficLightEnabled(const lanelet::Id lanelet_id) const -> bool;
264 
283  auto addTrafficSource(
284  const double radius, const double rate, const double speed,
285  const geometry_msgs::msg::Pose & position,
286  const traffic::TrafficSource::Distribution & distribution,
287  const bool allow_spawn_outside_lane = false, const bool require_footprint_fitting = false,
288  const bool random_orientation = false, std::optional<int> random_seed = std::nullopt) -> void;
289 
290 private:
291  auto updateTimeInSim() -> bool;
292 
293  auto updateEntitiesStatusInSim() -> bool;
294 
295  auto updateTrafficLightsInSim() -> bool;
296 
297  const Configuration configuration_;
298 
299  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
300 
301  const rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr clock_pub_;
302 
303  const rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_marker_pub_;
304 
305  SimulationClock clock_;
306 
307  zeromq::MultiClient zeromq_client_;
308 
309  const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
310 
311  const std::shared_ptr<traffic::TrafficController> traffic_controller_ptr_;
312 
313  const std::shared_ptr<TrafficLights> traffic_lights_ptr_;
314 
315  const rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr real_time_factor_subscriber_;
316 };
317 } // namespace traffic_simulator
318 
319 #endif // TRAFFIC_SIMULATOR__API__API_HPP_
Definition: api.hpp:57
auto isNpcLogicStarted() const -> bool
Definition: api.cpp:65
auto addTrafficSource(const double radius, const double rate, const double speed, const geometry_msgs::msg::Pose &position, const traffic::TrafficSource::Distribution &distribution, const bool allow_spawn_outside_lane=false, const bool require_footprint_fitting=false, const bool random_orientation=false, std::optional< int > random_seed=std::nullopt) -> void
Add a traffic source to the simulation.
Definition: api.cpp:392
auto checkCollision(const std::string &first_entity_name, const std::string &second_entity_name) const -> bool
Definition: api.cpp:345
API(NodeT &&node, const Configuration &configuration, Ts &&... xs)
Definition: api.hpp:60
auto getConventionalDetectedTrafficLights() const -> std::shared_ptr< DetectedTrafficLights >
Definition: api.cpp:377
auto setSimulationStepTime(const double step_time) -> bool
Definition: api.cpp:39
auto setTrafficSignalV2IFeature(const lanelet::Id lanelet_id, const bool enabled) -> void
Definition: api.cpp:382
auto attachOccupancyGridSensor(const simulation_api_schema::OccupancyGridSensorConfiguration &) -> bool
Definition: api.cpp:215
auto getEntity(const std::string &name) -> entity::EntityBase &
Definition: api.cpp:256
auto closeZMQConnection() -> void
Definition: api.cpp:69
auto getCurrentTime() const noexcept -> double
Definition: api.cpp:67
auto attachPseudoTrafficLightDetector(const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &) -> bool
Definition: api.cpp:162
auto isAnyEgoSpawned() const -> bool
Definition: api.cpp:228
auto setVerbose(const bool verbose) -> void
Definition: api.cpp:37
auto getFirstEgoName() const -> std::optional< std::string >
Definition: api.cpp:230
auto getEntityNames() const -> std::vector< std::string >
Definition: api.cpp:251
auto getEntityPointer(const std::string &name) const -> std::shared_ptr< entity::EntityBase >
Definition: api.cpp:266
auto resetBehaviorPlugin(const std::string &name, const std::string &behavior_plugin_name) -> void
Definition: api.cpp:272
auto getV2ITrafficLights() const -> std::shared_ptr< V2ITrafficLights >
Definition: api.cpp:362
auto getROS2Parameter(Ts &&... xs) const -> decltype(auto)
Definition: api.hpp:97
auto init() -> bool
Definition: api.cpp:21
auto startNpcLogic() -> void
Definition: api.cpp:55
auto attachLidarSensor(const simulation_api_schema::LidarConfiguration &) -> bool
Definition: api.cpp:170
auto spawn(const std::string &name, const PoseType &pose, const ParamsType &parameters, const std::string &behavior="", const std::string &model3d="") -> entity::EntityBase &
Definition: api.hpp:126
auto getV2IDetectedTrafficLights() const -> std::shared_ptr< DetectedTrafficLights >
Definition: api.cpp:372
auto attachDetectionSensor(const simulation_api_schema::DetectionSensorConfiguration &) -> bool
Definition: api.cpp:192
auto respawn(const std::string &name, const geometry_msgs::msg::PoseWithCovarianceStamped &new_pose, const geometry_msgs::msg::PoseStamped &goal_pose) -> void
Definition: api.cpp:278
auto getConventionalTrafficLights() const -> std::shared_ptr< ConventionalTrafficLights >
Definition: api.cpp:367
auto getEgoEntity(const std::string &name) -> entity::EgoEntity &
Definition: api.cpp:235
auto updateFrame() -> bool
Definition: api.cpp:126
auto despawnEntities() -> bool
Definition: api.cpp:337
auto attachImuSensor(const std::string &, const simulation_api_schema::ImuSensorConfiguration &configuration) -> bool
Definition: api.cpp:154
auto isV2ITrafficLightEnabled(const lanelet::Id lanelet_id) const -> bool
Definition: api.cpp:387
auto despawn(const std::string &name) -> bool
Definition: api.cpp:323
auto isEntityExist(const std::string &name) const -> bool
Definition: api.cpp:246
Definition: traffic_lights.hpp:36
Definition: traffic_lights.hpp:64
Definition: simulation_clock.hpp:24
Definition: traffic_lights.hpp:226
Definition: traffic_lights.hpp:110
Definition: ego_entity.hpp:35
Definition: entity_base.hpp:52
Definition: misc_object_entity.hpp:27
Definition: pedestrian_entity.hpp:34
Definition: vehicle_entity.hpp:37
auto call(const simulation_api_schema::SimulationRequest &) -> simulation_api_schema::SimulationResponse
Definition: zmq_multi_client.cpp:43
#define THROW_SEMANTIC_ERROR(...)
Definition: exception.hpp:59
Definition: concatenate.hpp:24
Definition: constants.hpp:21
void toProto(const geometry_msgs::msg::Point &p, geometry_msgs::Point &proto)
Definition: conversions.cpp:22
const TransportProtocol protocol
Definition: constants.hpp:30
Definition: lanelet_wrapper.hpp:43
LidarType
Definition: helper.hpp:141
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:71
Definition: operators.hpp:25
Definition: api.hpp:33
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: conversions.hpp:57
A problem occurred that interfered with the continuation of the simulation.
Definition: exception.hpp:47
Definition: configuration.hpp:30
bool verbose
Definition: configuration.hpp:35
const bool standalone_mode
Definition: configuration.hpp:39
static auto noBehavior() noexcept -> const std::string &
Definition: api.hpp:49
static auto autoware() noexcept -> const std::string &
Definition: api.hpp:36
static auto defaultBehavior() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:56
static auto defaultBehavior() -> const std::string &
Definition: vehicle_entity.hpp:59
class definition for the traffic controller