15 #ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__DETECTION_SENSOR__DETECTION_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__DETECTION_SENSOR__DETECTION_SENSOR_HPP_
18 #include <simulation_api_schema.pb.h>
23 #include <rclcpp/rclcpp.hpp>
38 const double current_simulation_time,
39 const simulation_api_schema::DetectionSensorConfiguration & configuration)
48 const std::vector<traffic_simulator_msgs::EntityStatus> &)
const
49 -> std::vector<traffic_simulator_msgs::EntityStatus>::const_iterator;
55 const double current_simulation_time,
const std::vector<traffic_simulator_msgs::EntityStatus> &,
56 const rclcpp::Time & current_ros_time,
57 const std::vector<std::string> & lidar_detected_entities) = 0;
60 template <
typename T,
typename U = autoware_auto_perception_msgs::msg::TrackedObjects>
63 const typename rclcpp::Publisher<T>::SharedPtr detected_objects_publisher;
65 const typename rclcpp::Publisher<U>::SharedPtr ground_truth_objects_publisher;
67 std::default_random_engine random_engine_;
69 std::queue<std::pair<autoware_auto_perception_msgs::msg::DetectedObjects, double>>
70 detected_objects_queue;
72 std::queue<std::pair<autoware_auto_perception_msgs::msg::TrackedObjects, double>>
73 ground_truth_objects_queue;
77 const double current_simulation_time,
78 const simulation_api_schema::DetectionSensorConfiguration & configuration,
79 const typename rclcpp::Publisher<T>::SharedPtr & publisher,
80 const typename rclcpp::Publisher<U>::SharedPtr & ground_truth_publisher =
nullptr)
82 detected_objects_publisher(publisher),
83 ground_truth_objects_publisher(ground_truth_publisher),
84 random_engine_(configuration.random_seed())
91 const double,
const std::vector<traffic_simulator_msgs::EntityStatus> &,
const rclcpp::Time &,
92 const std::vector<std::string> & lidar_detected_entities) ->
void override;
Definition: detection_sensor.hpp:31
DetectionSensorBase(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration)
Definition: detection_sensor.hpp:37
virtual ~DetectionSensorBase()=default
simulation_api_schema::DetectionSensorConfiguration configuration_
Definition: detection_sensor.hpp:35
auto isEgoEntityStatusToWhichThisSensorIsAttached(const traffic_simulator_msgs::EntityStatus &) const -> bool
Definition: detection_sensor.cpp:42
double previous_simulation_time_
Definition: detection_sensor.hpp:33
virtual void update(const double current_simulation_time, const std::vector< traffic_simulator_msgs::EntityStatus > &, const rclcpp::Time ¤t_ros_time, const std::vector< std::string > &lidar_detected_entities)=0
auto findEgoEntityStatusToWhichThisSensorIsAttached(const std::vector< traffic_simulator_msgs::EntityStatus > &) const -> std::vector< traffic_simulator_msgs::EntityStatus >::const_iterator
Definition: detection_sensor.cpp:49
Definition: detection_sensor.hpp:62
DetectionSensor(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration, const typename rclcpp::Publisher< T >::SharedPtr &publisher, const typename rclcpp::Publisher< U >::SharedPtr &ground_truth_publisher=nullptr)
Definition: detection_sensor.hpp:76
~DetectionSensor() override=default
auto update(const double, const std::vector< traffic_simulator_msgs::EntityStatus > &, const rclcpp::Time &, const std::vector< std::string > &lidar_detected_entities) -> void override
Definition: constants.hpp:19
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32