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_auto_perception_msgs/msg/detected_objects.hpp>
21 #include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
24 #include <rclcpp/rclcpp.hpp>
38 const double current_simulation_time,
39 const simulation_api_schema::LidarConfiguration & configuration, rclcpp::Node & node) ->
void
41 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
43 current_simulation_time, configuration,
44 node.create_publisher<sensor_msgs::msg::PointCloud2>(
45 "/perception/obstacle_segmentation/pointcloud", 1)));
48 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
50 throw std::runtime_error(ss.str());
55 const double current_simulation_time,
56 const simulation_api_schema::DetectionSensorConfiguration & configuration, rclcpp::Node & node)
59 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
60 using Message = autoware_auto_perception_msgs::msg::DetectedObjects;
61 using GroundTruthMessage = autoware_auto_perception_msgs::msg::TrackedObjects;
63 current_simulation_time, configuration,
64 node.create_publisher<Message>(
"/perception/object_recognition/detection/objects", 1),
65 node.create_publisher<GroundTruthMessage>(
66 "/perception/object_recognition/ground_truth/objects", 1)));
69 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
71 throw std::runtime_error(ss.str());
76 const double current_simulation_time,
77 const simulation_api_schema::OccupancyGridSensorConfiguration & configuration,
78 rclcpp::Node & node) ->
void
80 if (configuration.architecture_type().find(
"awf/universe") != std::string::npos) {
81 using Message = nav_msgs::msg::OccupancyGrid;
83 current_simulation_time, configuration,
84 node.create_publisher<Message>(
"/perception/occupancy_grid_map/map", 1)));
87 ss <<
"Unexpected architecture_type " << std::quoted(configuration.architecture_type())
89 throw std::runtime_error(ss.str());
95 const simulation_api_schema::PseudoTrafficLightDetectorConfiguration & configuration,
96 rclcpp::Node & node) ->
void
98 traffic_lights_detectors_.push_back(std::make_unique<traffic_lights::TrafficLightsDetector>(
99 node, configuration.architecture_type()));
104 const simulation_api_schema::ImuSensorConfiguration & configuration, rclcpp::Node & node)
108 configuration, node.create_publisher<sensor_msgs::msg::Imu>(
"/sensing/imu/imu_data", 1)));
112 double current_simulation_time,
const rclcpp::Time & current_ros_time,
113 const std::vector<traffic_simulator_msgs::EntityStatus> &,
114 const simulation_api_schema::UpdateTrafficLightsRequest &) -> void;
117 std::vector<std::unique_ptr<ImuSensorBase>> imu_sensors_;
118 std::vector<std::unique_ptr<LidarSensorBase>> lidar_sensors_;
119 std::vector<std::unique_ptr<DetectionSensorBase>> detection_sensors_;
120 std::vector<std::unique_ptr<OccupancyGridSensorBase>> occupancy_grid_sensors_;
121 std::vector<std::unique_ptr<traffic_lights::TrafficLightsDetector>> traffic_lights_detectors_;
Definition: detection_sensor.hpp:62
Definition: imu_sensor.hpp:76
Definition: lidar_sensor.hpp:60
occupancy grid sensor implementation
Definition: occupancy_grid_sensor.hpp:83
Definition: sensor_simulation.hpp:35
auto attachDetectionSensor(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:54
auto attachImuSensor(const double, const simulation_api_schema::ImuSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:102
auto attachOccupancyGridSensor(const double current_simulation_time, const simulation_api_schema::OccupancyGridSensorConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:75
auto attachLidarSensor(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration, rclcpp::Node &node) -> void
Definition: sensor_simulation.hpp:37
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:93
Definition: constants.hpp:19