15 #ifndef TRAFFIC_SIMULATOR__API__API_HPP_
16 #define TRAFFIC_SIMULATOR__API__API_HPP_
18 #include <simulation_api_schema.pb.h>
20 #include <boost/variant.hpp>
24 #include <rclcpp/rclcpp.hpp>
25 #include <rosgraph_msgs/msg/clock.hpp>
28 #include <std_msgs/msg/float64.hpp>
44 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
65 template <
typename NodeT,
typename AllocatorT = std::allocator<
void>,
typename... Ts>
67 : configuration(configuration),
69 rclcpp::node_interfaces::get_node_parameters_interface(
std::forward<NodeT>(node))),
71 std::make_shared<entity::EntityManager>(node, configuration, node_parameters_)),
75 traffic_controller_ptr_(
std::make_shared<traffic::TrafficController>(
76 entity_manager_ptr_, configuration.auto_sink_entity_types)),
77 clock_pub_(rclcpp::create_publisher<rosgraph_msgs::msg::Clock>(
78 node,
"/clock", rclcpp::QoS(rclcpp::KeepLast(1)).best_effort(),
79 rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
80 debug_marker_pub_(rclcpp::create_publisher<visualization_msgs::msg::MarkerArray>(
81 node,
"debug_marker", rclcpp::QoS(100), rclcpp::PublisherOptionsWithAllocator<AllocatorT>())),
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) {
89 if (message.data >= 0.001) {
91 simulation_api_schema::UpdateStepTimeRequest request;
92 request.set_simulation_step_time(clock_.
getStepTime());
93 zeromq_client_.
call(request);
96 clock_(node->get_parameter(
"use_sim_time").as_bool(), std::forward<decltype(
xs)>(
xs)...),
100 entity_manager_ptr_->setTrafficLights(traffic_lights_ptr_);
104 simulation_api_schema::InitializeRequest request;
111 if (not zeromq_client_.
call(request).result().success()) {
117 template <
typename ParameterT,
typename... Ts>
120 return getParameter<ParameterT>(node_parameters_, std::forward<Ts>(
xs)...);
123 template <
typename Node>
126 if (!node.has_parameter(
"port")) node.declare_parameter(
"port", 5555);
127 return node.get_parameter(
"port").as_int();
134 template <
typename Pose>
137 const traffic_simulator_msgs::msg::VehicleParameters & parameters,
141 auto register_to_entity_manager = [&]() {
143 return entity_manager_ptr_->entityExists(name) or
145 name, pose, parameters,
getCurrentTime(), configuration, node_parameters_);
152 auto register_to_environment_simulator = [&]() {
155 }
else if (
const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
157 "Entity ", name,
" can not be registered in simulator - it has not been spawned yet.");
159 simulation_api_schema::SpawnVehicleEntityRequest req;
161 req.mutable_parameters()->set_name(name);
162 req.set_asset_key(model3d);
166 req.set_initial_speed(0.0);
167 return zeromq_client_.
call(req).result().success();
171 return register_to_entity_manager() and register_to_environment_simulator();
174 template <
typename Pose>
177 const traffic_simulator_msgs::msg::PedestrianParameters & parameters,
181 auto register_to_entity_manager = [&]() {
186 auto register_to_environment_simulator = [&]() {
189 }
else if (
const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
191 "Entity ", name,
" can not be registered in simulator - it has not been spawned yet.");
193 simulation_api_schema::SpawnPedestrianEntityRequest req;
195 req.mutable_parameters()->set_name(name);
196 req.set_asset_key(model3d);
198 return zeromq_client_.
call(req).result().success();
202 return register_to_entity_manager() and register_to_environment_simulator();
205 template <
typename Pose>
208 const traffic_simulator_msgs::msg::MiscObjectParameters & parameters,
211 auto register_to_entity_manager = [&]() {
216 auto register_to_environment_simulator = [&]() {
219 }
else if (
const auto entity = entity_manager_ptr_->getEntity(name); not entity) {
221 "Entity ", name,
" can not be registered in simulator - it has not been spawned yet.");
223 simulation_api_schema::SpawnMiscObjectEntityRequest req;
225 req.mutable_parameters()->set_name(name);
226 req.set_asset_key(model3d);
228 return zeromq_client_.
call(req).result().success();
232 return register_to_entity_manager() and register_to_environment_simulator();
240 const std::string & name,
const geometry_msgs::msg::PoseWithCovarianceStamped & new_pose,
241 const geometry_msgs::msg::PoseStamped & goal_pose) -> void;
243 const std::string & name,
const geometry_msgs::msg::Pose & map_pose,
244 const traffic_simulator_msgs::msg::ActionStatus & action_status =
248 const traffic_simulator_msgs::msg::ActionStatus & action_status) -> void;
251 const traffic_simulator_msgs::msg::ActionStatus & action_status =
255 const geometry_msgs::msg::Pose & relative_pose,
256 const traffic_simulator_msgs::msg::ActionStatus & action_status =
260 const geometry_msgs::msg::Point & relative_position,
261 const geometry_msgs::msg::Vector3 & relative_rpy,
262 const traffic_simulator_msgs::msg::ActionStatus & action_status =
268 const std::string &,
const simulation_api_schema::ImuSensorConfiguration & configuration)
272 const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &);
276 const std::string &,
const double lidar_sensor_delay,
281 const std::string &,
double detection_sensor_range,
bool detect_all_objects_in_range,
282 double pos_noise_stddev,
int random_seed,
double probability_of_lost,
283 double object_recognition_delay);
328 const double radius,
const double rate,
const double speed,
329 const geometry_msgs::msg::Pose & position,
331 const bool allow_spawn_outside_lane =
false,
const bool require_footprint_fitting =
false,
332 const bool random_orientation =
false, std::optional<int> random_seed = std::nullopt) -> void;
338 return traffic_lights_ptr_->getConventionalTrafficLights();
344 #define FORWARD_TO_ENTITY_MANAGER(NAME) \
350 template <typename... Ts> \
351 decltype(auto) NAME(Ts &&... xs) \
353 assert(entity_manager_ptr_); \
354 return (*entity_manager_ptr_).NAME(std::forward<decltype(xs)>(xs)...); \
356 static_assert(true, "")
405 #undef FORWARD_TO_ENTITY_MANAGER
408 bool updateTimeInSim();
410 bool updateEntitiesStatusInSim();
412 bool updateTrafficLightsInSim();
416 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
418 const std::shared_ptr<entity::EntityManager> entity_manager_ptr_;
420 const std::shared_ptr<TrafficLights> traffic_lights_ptr_;
422 const std::shared_ptr<traffic::TrafficController> traffic_controller_ptr_;
424 const rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr clock_pub_;
426 const rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_marker_pub_;
428 const rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr real_time_factor_subscriber;
#define FORWARD_TO_ENTITY_MANAGER(NAME)
Definition: api.hpp:344
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::MiscObjectParameters ¶meters, const std::string &model3d="")
Definition: api.hpp:206
auto getV2ITrafficLights()
Definition: api.hpp:334
decltype(auto) getCanonicalizedStatusBeforeUpdate(Ts &&... xs)
Forward to arguments to the EntityManager:: getCanonicalizedStatusBeforeUpdate function.
Definition: api.hpp:368
decltype(auto) getHdmapUtils(Ts &&... xs)
Forward to arguments to the EntityManager:: getHdmapUtils function.
Definition: api.hpp:369
decltype(auto) requestFollowTrajectory(Ts &&... xs)
Forward to arguments to the EntityManager:: requestFollowTrajectory function.
Definition: api.hpp:380
double getCurrentTime() const noexcept
Definition: api.hpp:289
decltype(auto) resetBehaviorPlugin(Ts &&... xs)
Forward to arguments to the EntityManager:: resetBehaviorPlugin function.
Definition: api.hpp:385
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:373
decltype(auto) getTraveledDistance(Ts &&... xs)
Forward to arguments to the EntityManager:: getTraveledDistance function.
Definition: api.hpp:372
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:393
decltype(auto) setBehaviorParameter(Ts &&... xs)
Forward to arguments to the EntityManager:: setBehaviorParameter function.
Definition: api.hpp:389
void startNpcLogic()
Definition: api.cpp:365
auto getConventionalTrafficLights()
Definition: api.hpp:336
decltype(auto) isInLanelet(Ts &&... xs)
Forward to arguments to the EntityManager:: isInLanelet function.
Definition: api.hpp:374
decltype(auto) setDecelerationRateLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setDecelerationRateLimit function.
Definition: api.hpp:391
decltype(auto) requestWalkStraight(Ts &&... xs)
Forward to arguments to the EntityManager:: requestWalkStraight function.
Definition: api.hpp:383
int getZMQSocketPort(Node &node)
Definition: api.hpp:124
decltype(auto) getBoundingBox(Ts &&... xs)
Forward to arguments to the EntityManager:: getBoundingBox function.
Definition: api.hpp:361
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:371
decltype(auto) requestSynchronize(Ts &&... xs)
Forward to arguments to the EntityManager:: requestSynchronize function.
Definition: api.hpp:382
decltype(auto) setAccelerationLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setAccelerationLimit function.
Definition: api.hpp:387
decltype(auto) requestClearRoute(Ts &&... xs)
Forward to arguments to the EntityManager:: requestClearRoute function.
Definition: api.hpp:384
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:358
decltype(auto) reachPosition(Ts &&... xs)
Forward to arguments to the EntityManager:: reachPosition function.
Definition: api.hpp:377
decltype(auto) setAcceleration(Ts &&... xs)
Forward to arguments to the EntityManager:: setAcceleration function.
Definition: api.hpp:386
decltype(auto) getCurrentAccel(Ts &&... xs)
Forward to arguments to the EntityManager:: getCurrentAccel function.
Definition: api.hpp:362
auto getROS2Parameter(Ts &&... xs) const -> decltype(auto)
Definition: api.hpp:118
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::VehicleParameters ¶meters, const std::string &behavior=VehicleBehavior::defaultBehavior(), const std::string &model3d="")
Definition: api.hpp:135
decltype(auto) getLinearJerk(Ts &&... xs)
Forward to arguments to the EntityManager:: getLinearJerk function.
Definition: api.hpp:370
decltype(auto) getEntityStatus(Ts &&... xs)
Forward to arguments to the EntityManager:: getEntityStatus function.
Definition: api.hpp:367
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:394
decltype(auto) isNpcLogicStarted(Ts &&... xs)
Forward to arguments to the EntityManager:: isNpcLogicStarted function.
Definition: api.hpp:375
decltype(auto) getCurrentAction(Ts &&... xs)
Forward to arguments to the EntityManager:: getCurrentAction function.
Definition: api.hpp:363
auto spawn(const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::PedestrianParameters ¶meters, const std::string &behavior=PedestrianBehavior::defaultBehavior(), const std::string &model3d="")
Definition: api.hpp:175
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:376
void closeZMQConnection()
Definition: api.hpp:130
decltype(auto) getEntityNames(Ts &&... xs)
Forward to arguments to the EntityManager:: getEntityNames function.
Definition: api.hpp:366
decltype(auto) setAccelerationRateLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setAccelerationRateLimit function.
Definition: api.hpp:388
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:381
decltype(auto) setLinearVelocity(Ts &&... xs)
Forward to arguments to the EntityManager:: setLinearVelocity function.
Definition: api.hpp:392
decltype(auto) cancelRequest(Ts &&... xs)
Forward to arguments to the EntityManager:: cancelRequest function.
Definition: api.hpp:357
decltype(auto) setDecelerationLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setDecelerationLimit function.
Definition: api.hpp:390
bool despawnEntities()
Definition: api.cpp:47
decltype(auto) setVelocityLimit(Ts &&... xs)
Forward to arguments to the EntityManager:: setVelocityLimit function.
Definition: api.hpp:395
decltype(auto) entityExists(Ts &&... xs)
Forward to arguments to the EntityManager:: entityExists function.
Definition: api.hpp:359
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:364
decltype(auto) activateOutOfRangeJob(Ts &&... xs)
Forward to arguments to the EntityManager:: activateOutOfRangeJob function.
Definition: api.hpp:355
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:365
decltype(auto) asFieldOperatorApplication(Ts &&... xs)
Forward to arguments to the EntityManager:: asFieldOperatorApplication function.
Definition: api.hpp:356
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:379
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:360
bool updateFrame()
Definition: api.cpp:338
decltype(auto) requestAcquirePosition(Ts &&... xs)
Forward to arguments to the EntityManager:: requestAcquirePosition function.
Definition: api.hpp:378
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
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
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
Definition: pedestrian_entity.hpp:37
static auto defaultBehavior() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:56
Definition: vehicle_entity.hpp:40
static auto defaultBehavior() -> const std::string &
Definition: vehicle_entity.hpp:59
Definition: lane_change.hpp:34
Definition: lane_change.hpp:44
parameters for behavior plugin
Definition: lane_change.hpp:75
Definition: lane_change.hpp:58
class definition for the traffic controller