15 #ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__SENSOR_SIMULATION_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__SENSOR_SIMULATION_HPP_
18 #include <simulation_api_schema.pb.h>
20 #include <autoware_perception_msgs/msg/detected_objects.hpp>
21 #include <autoware_perception_msgs/msg/tracked_objects.hpp>
24 #include <rclcpp/rclcpp.hpp>
33 #if __has_include(<autoware_perception_msgs/msg/traffic_signal_array.hpp>)
34 #include <autoware_perception_msgs/msg/traffic_signal_array.hpp>
37 #if __has_include(<autoware_perception_msgs/msg/traffic_light_group_array.hpp>)
38 #include <autoware_perception_msgs/msg/traffic_light_group_array.hpp>
47 const double current_simulation_time,
48 const simulation_api_schema::LidarConfiguration & configuration, rclcpp::Node & node) ->
void
50 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
52 current_simulation_time, configuration,
53 node.create_publisher<sensor_msgs::msg::PointCloud2>(
54 "/perception/obstacle_segmentation/pointcloud", 1)));
57 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
59 throw std::runtime_error(ss.str());
64 const double current_simulation_time,
65 const simulation_api_schema::DetectionSensorConfiguration & configuration, rclcpp::Node & node)
68 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
69 using Message = autoware_perception_msgs::msg::DetectedObjects;
70 using GroundTruthMessage = autoware_perception_msgs::msg::TrackedObjects;
72 current_simulation_time, configuration,
73 node.create_publisher<Message>(
"/perception/object_recognition/detection/objects", 1),
74 node.create_publisher<GroundTruthMessage>(
75 "/perception/object_recognition/ground_truth/objects", 1)));
78 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
80 throw std::runtime_error(ss.str());
85 const double current_simulation_time,
86 const simulation_api_schema::OccupancyGridSensorConfiguration & configuration,
87 rclcpp::Node & node) ->
void
89 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
90 using Message = nav_msgs::msg::OccupancyGrid;
92 current_simulation_time, configuration,
93 node.create_publisher<Message>(
"/perception/occupancy_grid_map/map", 1)));
96 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
98 throw std::runtime_error(ss.str());
104 const simulation_api_schema::PseudoTrafficLightDetectorConfiguration & configuration,
105 rclcpp::Node & node) ->
void
107 traffic_lights_detectors_.push_back(std::make_unique<traffic_lights::TrafficLightsDetector>(
108 node, configuration.architecture_type()));
113 const simulation_api_schema::ImuSensorConfiguration & configuration, rclcpp::Node & node)
117 configuration, node.create_publisher<sensor_msgs::msg::Imu>(
"/sensing/imu/imu_data", 1)));
121 double current_simulation_time,
const rclcpp::Time & current_ros_time,
122 const std::vector<traffic_simulator_msgs::EntityStatus> &,
123 const simulation_api_schema::UpdateTrafficLightsRequest &) -> void;
126 std::vector<std::unique_ptr<ImuSensorBase>> imu_sensors_;
127 std::vector<std::unique_ptr<LidarSensorBase>> lidar_sensors_;
128 std::vector<std::unique_ptr<DetectionSensorBase>> detection_sensors_;
129 std::vector<std::unique_ptr<OccupancyGridSensorBase>> occupancy_grid_sensors_;
130 std::vector<std::unique_ptr<traffic_lights::TrafficLightsDetector>> traffic_lights_detectors_;
Definition: detection_sensor.hpp:72
Definition: imu_sensor.hpp:76
Definition: lidar_sensor.hpp:60
occupancy grid sensor implementation
Definition: occupancy_grid_sensor.hpp:83
Definition: sensor_simulation.hpp:44
auto attachDetectionSensor(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:63
auto attachImuSensor(const double, const simulation_api_schema::ImuSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:111
auto attachOccupancyGridSensor(const double current_simulation_time, const simulation_api_schema::OccupancyGridSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:84
auto attachLidarSensor(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:46
auto updateSensorFrame(double current_simulation_time, const rclcpp::Time ¤t_ros_time, const std::vector< traffic_simulator_msgs::EntityStatus > &, const simulation_api_schema::UpdateTrafficLightsRequest &) -> void
Definition: sensor_simulation.cpp:22
auto attachPseudoTrafficLightsDetector(const double, const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:102
Definition: constants.hpp:19