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_api_schema.pb.h>
19 
20 #include <boost/variant.hpp>
21 #include <cassert>
22 #include <memory>
23 #include <optional>
24 #include <rclcpp/rclcpp.hpp>
25 #include <rosgraph_msgs/msg/clock.hpp>
28 #include <std_msgs/msg/float64.hpp>
29 #include <stdexcept>
30 #include <string>
44 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
45 #include <utility>
46 
48 {
50 {
51  static auto autoware() noexcept -> const std::string &
52  {
53  static const std::string name = "Autoware";
54  return name;
55  }
56 };
57 
59 {
60 };
61 
62 class API
63 {
64 public:
65  template <typename NodeT, typename AllocatorT = std::allocator<void>, typename... Ts>
66  explicit API(NodeT && node, const Configuration & configuration, Ts &&... xs)
67  : configuration(configuration),
68  node_parameters_(
69  rclcpp::node_interfaces::get_node_parameters_interface(std::forward<NodeT>(node))),
70  entity_manager_ptr_(
71  std::make_shared<entity::EntityManager>(node, configuration, node_parameters_)),
72  traffic_lights_ptr_(std::make_shared<TrafficLights>(
73  node, entity_manager_ptr_->getHdmapUtils(),
74  getROS2Parameter<std::string>("architecture_type", "awf/universe/20240605"))),
75  traffic_controller_ptr_(std::make_shared<traffic::TrafficController>(
76  [this](const std::string & name) { despawn(name); }, entity_manager_ptr_,
77  configuration.auto_sink_entity_types)),
78  clock_pub_(rclcpp::create_publisher<rosgraph_msgs::msg::Clock>(
79  node, "/clock", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
80  rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
81  debug_marker_pub_(rclcpp::create_publisher<visualization_msgs::msg::MarkerArray>(
82  node, "debug_marker", rclcpp::QoS(100), rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
83  real_time_factor_subscriber(rclcpp::create_subscription<std_msgs::msg::Float64>(
84  node, "/real_time_factor", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
85  [this](const std_msgs::msg::Float64 & message) {
90  if (message.data >= 0.001) {
91  clock_.realtime_factor = message.data;
92  simulation_api_schema::UpdateStepTimeRequest request;
93  request.set_simulation_step_time(clock_.getStepTime());
94  zeromq_client_.call(request);
95  }
96  })),
97  clock_(node->get_parameter("use_sim_time").as_bool(), std::forward<decltype(xs)>(xs)...),
98  zeromq_client_(
99  simulation_interface::protocol, configuration.simulator_host, getZMQSocketPort(*node))
100  {
101  entity_manager_ptr_->setTrafficLights(traffic_lights_ptr_);
102  setVerbose(configuration.verbose);
103 
104  if (not configuration.standalone_mode) {
105  simulation_api_schema::InitializeRequest request;
106  request.set_initialize_time(clock_.getCurrentSimulationTime());
107  request.set_lanelet2_map_path(configuration.lanelet2_map_path().string());
108  request.set_realtime_factor(clock_.realtime_factor);
109  request.set_step_time(clock_.getStepTime());
111  clock_.getCurrentRosTime(), *request.mutable_initialize_ros_time());
112  if (not zeromq_client_.call(request).result().success()) {
113  throw common::SimulationError("Failed to initialize simulator by InitializeRequest");
114  }
115  }
116  }
117 
118  template <typename ParameterT, typename... Ts>
119  auto getROS2Parameter(Ts &&... xs) const -> decltype(auto)
120  {
121  return getParameter<ParameterT>(node_parameters_, std::forward<Ts>(xs)...);
122  }
123 
124  template <typename Node>
125  int getZMQSocketPort(Node & node)
126  {
127  if (!node.has_parameter("port")) node.declare_parameter("port", 5555);
128  return node.get_parameter("port").as_int();
129  }
130 
131  void closeZMQConnection() { zeromq_client_.closeConnection(); }
132 
133  void setVerbose(const bool verbose);
134 
135  template <typename Pose>
136  auto spawn(
137  const std::string & name, const Pose & pose,
138  const traffic_simulator_msgs::msg::VehicleParameters & parameters,
139  const std::string & behavior = VehicleBehavior::defaultBehavior(),
140  const std::string & model3d = "")
141  {
142  auto register_to_entity_manager = [&]() {
143  if (behavior == VehicleBehavior::autoware()) {
144  return entity_manager_ptr_->entityExists(name) or
145  entity_manager_ptr_->spawnEntity<entity::EgoEntity>(
146  name, pose, parameters, getCurrentTime(), configuration, node_parameters_);
147  } else {
148  return entity_manager_ptr_->spawnEntity<entity::VehicleEntity>(
149  name, pose, parameters, getCurrentTime(), behavior);
150  }
151  };
152 
153  auto register_to_environment_simulator = [&]() {
154  if (configuration.standalone_mode) {
155  return true;
156  } else if (const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
157  throw common::SemanticError(
158  "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
159  } else {
160  simulation_api_schema::SpawnVehicleEntityRequest req;
161  simulation_interface::toProto(parameters, *req.mutable_parameters());
162  req.mutable_parameters()->set_name(name);
163  req.set_asset_key(model3d);
164  simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
165  req.set_is_ego(behavior == VehicleBehavior::autoware());
167  req.set_initial_speed(0.0);
168  return zeromq_client_.call(req).result().success();
169  }
170  };
171 
172  return register_to_entity_manager() and register_to_environment_simulator();
173  }
174 
175  template <typename Pose>
176  auto spawn(
177  const std::string & name, const Pose & pose,
178  const traffic_simulator_msgs::msg::PedestrianParameters & parameters,
180  const std::string & model3d = "")
181  {
182  auto register_to_entity_manager = [&]() {
183  return entity_manager_ptr_->spawnEntity<entity::PedestrianEntity>(
184  name, pose, parameters, getCurrentTime(), behavior);
185  };
186 
187  auto register_to_environment_simulator = [&]() {
188  if (configuration.standalone_mode) {
189  return true;
190  } else if (const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
191  throw common::SemanticError(
192  "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
193  } else {
194  simulation_api_schema::SpawnPedestrianEntityRequest req;
195  simulation_interface::toProto(parameters, *req.mutable_parameters());
196  req.mutable_parameters()->set_name(name);
197  req.set_asset_key(model3d);
198  simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
199  return zeromq_client_.call(req).result().success();
200  }
201  };
202 
203  return register_to_entity_manager() and register_to_environment_simulator();
204  }
205 
206  template <typename Pose>
207  auto spawn(
208  const std::string & name, const Pose & pose,
209  const traffic_simulator_msgs::msg::MiscObjectParameters & parameters,
210  const std::string & model3d = "")
211  {
212  auto register_to_entity_manager = [&]() {
213  return entity_manager_ptr_->spawnEntity<entity::MiscObjectEntity>(
214  name, pose, parameters, getCurrentTime());
215  };
216 
217  auto register_to_environment_simulator = [&]() {
218  if (configuration.standalone_mode) {
219  return true;
220  } else if (const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
221  throw common::SemanticError(
222  "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
223  } else {
224  simulation_api_schema::SpawnMiscObjectEntityRequest req;
225  simulation_interface::toProto(parameters, *req.mutable_parameters());
226  req.mutable_parameters()->set_name(name);
227  req.set_asset_key(model3d);
228  simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
229  return zeromq_client_.call(req).result().success();
230  }
231  };
232 
233  return register_to_entity_manager() and register_to_environment_simulator();
234  }
235 
236  bool despawn(const std::string & name);
237  bool despawnEntities();
238 
239  auto setEntityStatus(const std::string & name, const EntityStatus & status) -> void;
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  auto setEntityStatus(
244  const std::string & name, const geometry_msgs::msg::Pose & map_pose,
245  const traffic_simulator_msgs::msg::ActionStatus & action_status =
247  auto setEntityStatus(
248  const std::string & name, const LaneletPose & lanelet_pose,
249  const traffic_simulator_msgs::msg::ActionStatus & action_status) -> void;
250  auto setEntityStatus(
251  const std::string & name, const CanonicalizedLaneletPose & canonicalized_lanelet_pose,
252  const traffic_simulator_msgs::msg::ActionStatus & action_status =
254  auto setEntityStatus(
255  const std::string & name, const std::string & reference_entity_name,
256  const geometry_msgs::msg::Pose & relative_pose,
257  const traffic_simulator_msgs::msg::ActionStatus & action_status =
259  auto setEntityStatus(
260  const std::string & name, const std::string & reference_entity_name,
261  const geometry_msgs::msg::Point & relative_position,
262  const geometry_msgs::msg::Vector3 & relative_rpy,
263  const traffic_simulator_msgs::msg::ActionStatus & action_status =
265 
266  std::optional<double> getTimeHeadway(const std::string & from, const std::string & to);
267 
268  auto attachImuSensor(
269  const std::string &, const simulation_api_schema::ImuSensorConfiguration & configuration)
270  -> bool;
271 
273  const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &);
274 
275  bool attachLidarSensor(const simulation_api_schema::LidarConfiguration &);
276  bool attachLidarSensor(
277  const std::string &, const double lidar_sensor_delay,
279 
280  bool attachDetectionSensor(const simulation_api_schema::DetectionSensorConfiguration &);
282  const std::string &, double detection_sensor_range, bool detect_all_objects_in_range,
283  double pos_noise_stddev, int random_seed, double probability_of_lost,
284  double object_recognition_delay);
285 
286  bool attachOccupancyGridSensor(const simulation_api_schema::OccupancyGridSensorConfiguration &);
287 
288  bool updateFrame();
289 
290  double getCurrentTime() const noexcept { return clock_.getCurrentScenarioTime(); }
291 
292  void startNpcLogic();
293 
294  void requestLaneChange(const std::string & name, const lanelet::Id & lanelet_id);
295 
296  void requestLaneChange(const std::string & name, const lane_change::Direction & direction);
297 
298  void requestLaneChange(const std::string & name, const lane_change::Parameter &);
299 
300  void requestLaneChange(
301  const std::string & name, const lane_change::RelativeTarget & target,
302  const lane_change::TrajectoryShape trajectory_shape,
303  const lane_change::Constraint & constraint);
304 
305  void requestLaneChange(
306  const std::string & name, const lane_change::AbsoluteTarget & target,
307  const lane_change::TrajectoryShape trajectory_shape,
308  const lane_change::Constraint & constraint);
309 
328  auto addTrafficSource(
329  const double radius, const double rate, const double speed,
330  const geometry_msgs::msg::Pose & position,
331  const traffic::TrafficSource::Distribution & distribution,
332  const bool allow_spawn_outside_lane = false, const bool require_footprint_fitting = false,
333  const bool random_orientation = false, std::optional<int> random_seed = std::nullopt) -> void;
334 
335  auto getV2ITrafficLights() { return traffic_lights_ptr_->getV2ITrafficLights(); }
336 
338  {
339  return traffic_lights_ptr_->getConventionalTrafficLights();
340  }
341 
342  auto getEntity(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;
343 
344  // clang-format off
345 #define FORWARD_TO_ENTITY_MANAGER(NAME) \
346  \
351  template <typename... Ts> \
352  decltype(auto) NAME(Ts &&... xs) \
353  { \
354  assert(entity_manager_ptr_); \
355  return (*entity_manager_ptr_).NAME(std::forward<decltype(xs)>(xs)...); \
356  } \
357  static_assert(true, "")
358  // clang-format on
359 
401 
402 private:
403  FORWARD_TO_ENTITY_MANAGER(getDefaultMatchingDistanceForLaneletPoseCalculation);
404 
405 public:
406 #undef FORWARD_TO_ENTITY_MANAGER
407 
408 private:
409  bool updateTimeInSim();
410 
411  bool updateEntitiesStatusInSim();
412 
413  bool updateTrafficLightsInSim();
414 
415  const Configuration configuration;
416 
417  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
418 
419  const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
420 
421  const std::shared_ptr<TrafficLights> traffic_lights_ptr_;
422 
423  const std::shared_ptr<traffic::TrafficController> traffic_controller_ptr_;
424 
425  const rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr clock_pub_;
426 
427  const rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_marker_pub_;
428 
429  const rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr real_time_factor_subscriber;
430 
431  SimulationClock clock_;
432 
433  zeromq::MultiClient zeromq_client_;
434 };
435 } // namespace traffic_simulator
436 
437 #endif // TRAFFIC_SIMULATOR__API__API_HPP_
#define FORWARD_TO_ENTITY_MANAGER(NAME)
Definition: api.hpp:345
Definition: api.hpp:63
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::MiscObjectParameters &parameters, const std::string &model3d="")
Definition: api.hpp:207
auto getV2ITrafficLights()
Definition: api.hpp:335
decltype(auto) getCanonicalizedStatusBeforeUpdate(Ts &&... xs)
Forward to arguments to the EntityManager:: getCanonicalizedStatusBeforeUpdate function.
Definition: api.hpp:369
decltype(auto) getHdmapUtils(Ts &&... xs)
Forward to arguments to the EntityManager:: getHdmapUtils function.
Definition: api.hpp:370
decltype(auto) requestFollowTrajectory(Ts &&... xs)
Forward to arguments to the EntityManager:: requestFollowTrajectory function.
Definition: api.hpp:381
double getCurrentTime() const noexcept
Definition: api.hpp:290
decltype(auto) resetBehaviorPlugin(Ts &&... xs)
Forward to arguments to the EntityManager:: resetBehaviorPlugin function.
Definition: api.hpp:386
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:408
API(NodeT &&node, const Configuration &configuration, Ts &&... xs)
Definition: api.hpp:66
decltype(auto) isEgoSpawned(Ts &&... xs)
Forward to arguments to the EntityManager:: isEgoSpawned function.
Definition: api.hpp:374
decltype(auto) getTraveledDistance(Ts &&... xs)
Forward to arguments to the EntityManager:: getTraveledDistance function.
Definition: api.hpp:373
void requestLaneChange(const std::string &name, const lanelet::Id &lanelet_id)
Definition: api.cpp:375
auto setEntityStatus(const std::string &name, const EntityStatus &status) -> void
Definition: api.cpp:124
decltype(auto) setMapPose(Ts &&... xs)
Forward to arguments to the EntityManager:: setMapPose function.
Definition: api.hpp:394
decltype(auto) setBehaviorParameter(Ts &&... xs)
Forward to arguments to the EntityManager:: setBehaviorParameter function.
Definition: api.hpp:390
void startNpcLogic()
Definition: api.cpp:365
auto getConventionalTrafficLights()
Definition: api.hpp:337
decltype(auto) isInLanelet(Ts &&... xs)
Forward to arguments to the EntityManager:: isInLanelet function.
Definition: api.hpp:375
decltype(auto) setDecelerationRateLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setDecelerationRateLimit function.
Definition: api.hpp:392
decltype(auto) requestWalkStraight(Ts &&... xs)
Forward to arguments to the EntityManager:: requestWalkStraight function.
Definition: api.hpp:384
int getZMQSocketPort(Node &node)
Definition: api.hpp:125
decltype(auto) getBoundingBox(Ts &&... xs)
Forward to arguments to the EntityManager:: getBoundingBox function.
Definition: api.hpp:362
bool attachOccupancyGridSensor(const simulation_api_schema::OccupancyGridSensorConfiguration &)
Definition: api.cpp:249
decltype(auto) getStandStillDuration(Ts &&... xs)
Forward to arguments to the EntityManager:: getStandStillDuration function.
Definition: api.hpp:372
decltype(auto) requestSynchronize(Ts &&... xs)
Forward to arguments to the EntityManager:: requestSynchronize function.
Definition: api.hpp:383
decltype(auto) setAccelerationLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setAccelerationLimit function.
Definition: api.hpp:388
decltype(auto) requestClearRoute(Ts &&... xs)
Forward to arguments to the EntityManager:: requestClearRoute function.
Definition: api.hpp:385
void setVerbose(const bool verbose)
Definition: api.cpp:31
decltype(auto) checkCollision(Ts &&... xs)
Forward to arguments to the EntityManager:: checkCollision function.
Definition: api.hpp:359
decltype(auto) reachPosition(Ts &&... xs)
Forward to arguments to the EntityManager:: reachPosition function.
Definition: api.hpp:378
decltype(auto) setAcceleration(Ts &&... xs)
Forward to arguments to the EntityManager:: setAcceleration function.
Definition: api.hpp:387
decltype(auto) getCurrentAccel(Ts &&... xs)
Forward to arguments to the EntityManager:: getCurrentAccel function.
Definition: api.hpp:363
auto getROS2Parameter(Ts &&... xs) const -> decltype(auto)
Definition: api.hpp:119
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::VehicleParameters &parameters, const std::string &behavior=VehicleBehavior::defaultBehavior(), const std::string &model3d="")
Definition: api.hpp:136
decltype(auto) getLinearJerk(Ts &&... xs)
Forward to arguments to the EntityManager:: getLinearJerk function.
Definition: api.hpp:371
decltype(auto) getEntityStatus(Ts &&... xs)
Forward to arguments to the EntityManager:: getEntityStatus function.
Definition: api.hpp:368
bool attachDetectionSensor(const simulation_api_schema::DetectionSensorConfiguration &)
Definition: api.cpp:226
std::optional< double > getTimeHeadway(const std::string &from, const std::string &to)
Definition: api.cpp:134
decltype(auto) setTwist(Ts &&... xs)
Forward to arguments to the EntityManager:: setTwist function.
Definition: api.hpp:395
decltype(auto) isNpcLogicStarted(Ts &&... xs)
Forward to arguments to the EntityManager:: isNpcLogicStarted function.
Definition: api.hpp:376
decltype(auto) getCurrentAction(Ts &&... xs)
Forward to arguments to the EntityManager:: getCurrentAction function.
Definition: api.hpp:364
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::PedestrianParameters &parameters, const std::string &behavior=PedestrianBehavior::defaultBehavior(), const std::string &model3d="")
Definition: api.hpp:176
auto respawn(const std::string &name, const geometry_msgs::msg::PoseWithCovarianceStamped &new_pose, const geometry_msgs::msg::PoseStamped &goal_pose) -> void
Definition: api.cpp:54
decltype(auto) laneMatchingSucceed(Ts &&... xs)
Forward to arguments to the EntityManager:: laneMatchingSucceed function.
Definition: api.hpp:377
void closeZMQConnection()
Definition: api.hpp:131
decltype(auto) getEntityNames(Ts &&... xs)
Forward to arguments to the EntityManager:: getEntityNames function.
Definition: api.hpp:367
decltype(auto) setAccelerationRateLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setAccelerationRateLimit function.
Definition: api.hpp:389
bool attachPseudoTrafficLightDetector(const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &)
Definition: api.cpp:218
decltype(auto) requestSpeedChange(Ts &&... xs)
Forward to arguments to the EntityManager:: requestSpeedChange function.
Definition: api.hpp:382
decltype(auto) setLinearVelocity(Ts &&... xs)
Forward to arguments to the EntityManager:: setLinearVelocity function.
Definition: api.hpp:393
decltype(auto) cancelRequest(Ts &&... xs)
Forward to arguments to the EntityManager:: cancelRequest function.
Definition: api.hpp:358
decltype(auto) setDecelerationLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setDecelerationLimit function.
Definition: api.hpp:391
bool despawnEntities()
Definition: api.cpp:47
decltype(auto) setVelocityLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setVelocityLimit function.
Definition: api.hpp:396
decltype(auto) entityExists(Ts &&... xs)
Forward to arguments to the EntityManager:: entityExists function.
Definition: api.hpp:360
bool despawn(const std::string &name)
Definition: api.cpp:33
decltype(auto) getCurrentTwist(Ts &&... xs)
Forward to arguments to the EntityManager:: getCurrentTwist function.
Definition: api.hpp:365
decltype(auto) activateOutOfRangeJob(Ts &&... xs)
Forward to arguments to the EntityManager:: activateOutOfRangeJob function.
Definition: api.hpp:356
bool attachLidarSensor(const simulation_api_schema::LidarConfiguration &)
Definition: api.cpp:261
decltype(auto) getEgoName(Ts &&... xs)
Forward to arguments to the EntityManager:: getEgoName function.
Definition: api.hpp:366
decltype(auto) asFieldOperatorApplication(Ts &&... xs)
Forward to arguments to the EntityManager:: asFieldOperatorApplication function.
Definition: api.hpp:357
auto getEntity(const std::string &name) const -> std::shared_ptr< entity::EntityBase >
Definition: api.cpp:103
decltype(auto) requestAssignRoute(Ts &&... xs)
Forward to arguments to the EntityManager:: requestAssignRoute function.
Definition: api.hpp:380
auto attachImuSensor(const std::string &, const simulation_api_schema::ImuSensorConfiguration &configuration) -> bool
Definition: api.cpp:210
decltype(auto) getBehaviorParameter(Ts &&... xs)
Forward to arguments to the EntityManager:: getBehaviorParameter function.
Definition: api.hpp:361
bool updateFrame()
Definition: api.cpp:338
decltype(auto) requestAcquirePosition(Ts &&... xs)
Forward to arguments to the EntityManager:: requestAcquirePosition function.
Definition: api.hpp:379
Definition: simulation_clock.hpp:24
auto getCurrentRosTime() -> rclcpp::Time
Definition: simulation_clock.cpp:41
double realtime_factor
Definition: simulation_clock.hpp:49
auto getCurrentScenarioTime() const
Definition: simulation_clock.hpp:32
auto getCurrentSimulationTime() const
Definition: simulation_clock.hpp:37
auto getStepTime() const
Definition: simulation_clock.hpp:39
Definition: traffic_lights.hpp:132
Definition: ego_entity.hpp:35
Definition: misc_object_entity.hpp:27
Definition: pedestrian_entity.hpp:34
Definition: vehicle_entity.hpp:37
Definition: lanelet_pose.hpp:27
std::vector< std::tuple< VehicleOrPedestrianParameter, std::string, std::string, double > > Distribution
Definition: traffic_source.hpp:69
Definition: zmq_multi_client.hpp:33
void closeConnection()
Definition: zmq_multi_client.cpp:33
auto call(const simulation_api_schema::SimulationRequest &) -> simulation_api_schema::SimulationResponse
Definition: zmq_multi_client.cpp:43
void toProto(const geometry_msgs::msg::Point &p, geometry_msgs::Point &proto)
Definition: conversions.cpp:22
const TransportProtocol protocol
Definition: constants.hpp:30
Definition: cache.hpp:27
traffic_simulator_msgs::msg::ActionStatus constructActionStatus(double linear_vel=0, double angular_vel=0, double linear_accel=0, double angular_accel=0)
helper function for constructing action status
Definition: helper.cpp:25
LidarType
Definition: helper.hpp:145
TrajectoryShape
Definition: lane_change.hpp:31
Direction
Definition: lane_change.hpp:29
Definition: api.hpp:48
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Although there were no syntactic errors in the description of the scenario, differences in meaning an...
Definition: exception.hpp:44
A problem occurred that interfered with the continuation of the simulation.
Definition: exception.hpp:47
Definition: configuration.hpp:30
auto lanelet2_map_path() const
Definition: configuration.hpp:134
bool standalone_mode
Definition: configuration.hpp:39
bool verbose
Definition: configuration.hpp:37
static auto autoware() noexcept -> const std::string &
Definition: api.hpp:51
static auto defaultBehavior() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:56
static auto defaultBehavior() -> const std::string &
Definition: vehicle_entity.hpp:59
Definition: lane_change.hpp:44
parameters for behavior plugin
Definition: lane_change.hpp:75
class definition for the traffic controller