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>
22 #include <geometry_msgs/msg/pose.hpp>
27 #include <rclcpp/rclcpp.hpp>
30 #include <unordered_map>
44 const double current_simulation_time,
45 const simulation_api_schema::DetectionSensorConfiguration & configuration)
54 const std::vector<traffic_simulator_msgs::EntityStatus> &)
const
55 -> std::vector<traffic_simulator_msgs::EntityStatus>::const_iterator;
64 const double current_simulation_time,
const std::vector<traffic_simulator_msgs::EntityStatus> &,
65 const rclcpp::Time & current_ros_time,
66 const std::vector<std::string> & lidar_detected_entities) = 0;
69 std::optional<math::geometry::Plane> ego_plane_opt_{std::nullopt};
70 std::optional<geometry_msgs::msg::Pose> ego_plane_pose_opt_{std::nullopt};
73 template <
typename T,
typename U = autoware_perception_msgs::msg::TrackedObjects>
76 const typename rclcpp::Publisher<T>::SharedPtr detected_objects_publisher;
78 const typename rclcpp::Publisher<U>::SharedPtr ground_truth_objects_publisher;
80 int noise_model_version;
82 std::default_random_engine random_engine_;
84 std::queue<std::pair<std::vector<traffic_simulator_msgs::EntityStatus>,
double>>
85 unpublished_detected_entities, unpublished_ground_truth_entities;
89 double simulation_time, distance_noise, yaw_noise;
91 bool true_positive, flip;
93 explicit NoiseOutput(
double simulation_time = 0.0)
94 : simulation_time(simulation_time),
103 std::unordered_map<std::string, NoiseOutput> noise_outputs;
105 template <
typename Message,
typename std::enable_if_t<std::is_same_v<Message, T>,
int> = 0>
108 static const auto override_legacy_configuration = concealer::getParameter<bool>(
109 detected_objects_publisher->get_topic_name() +
std::string(
".override_legacy_configuration"));
110 if (override_legacy_configuration) {
111 static const auto delay = concealer::getParameter<double>(
112 detected_objects_publisher->get_topic_name() +
std::string(
".delay"));
119 template <
typename Message,
typename std::enable_if_t<std::is_same_v<Message, U>,
int> = 0>
122 static const auto override_legacy_configuration = concealer::getParameter<bool>(
123 ground_truth_objects_publisher->get_topic_name() +
125 if (override_legacy_configuration) {
126 static const auto delay = concealer::getParameter<double>(
127 ground_truth_objects_publisher->get_topic_name() +
std::string(
".delay"));
136 static const auto override_legacy_configuration = concealer::getParameter<bool>(
137 detected_objects_publisher->get_topic_name() +
std::string(
".override_legacy_configuration"));
138 if (override_legacy_configuration) {
139 static const auto range = concealer::getParameter<double>(
140 detected_objects_publisher->get_topic_name() +
std::string(
".range"), 300.0);
147 auto detect_all_objects_in_range()
const
150 static const auto override_legacy_configuration = concealer::getParameter<bool>(
151 detected_objects_publisher->get_topic_name() +
std::string(
".override_legacy_configuration"));
152 if (override_legacy_configuration) {
153 static const auto occlusionless = concealer::getParameter<bool>(
154 detected_objects_publisher->get_topic_name() +
std::string(
".occlusionless"));
155 return occlusionless;
163 const double current_simulation_time,
164 const simulation_api_schema::DetectionSensorConfiguration & configuration,
165 const typename rclcpp::Publisher<T>::SharedPtr & publisher,
166 const typename rclcpp::Publisher<U>::SharedPtr & ground_truth_publisher =
nullptr)
168 detected_objects_publisher(publisher),
169 ground_truth_objects_publisher(ground_truth_publisher),
171 detected_objects_publisher->get_topic_name() +
std::
string(
".noise.model.version"))),
172 random_engine_([this]() {
173 if (
const auto seed = [
this]() -> std::random_device::result_type {
174 switch (noise_model_version) {
180 return concealer::getParameter<int>(
181 detected_objects_publisher->get_topic_name() +
std::string(
".seed"));
185 if (std::random_device::min() <= seed and seed <= std::random_device::max()) {
189 "The value of parameter ",
190 std::quoted(detected_objects_publisher->get_topic_name() +
std::string(
".seed")),
191 " must be greater than or equal to ", std::random_device::min(),
192 " and less than or equal to ", std::random_device::max());
195 return std::random_device()();
204 const double,
const std::vector<traffic_simulator_msgs::EntityStatus> &,
const rclcpp::Time &,
205 const std::vector<std::string> & lidar_detected_entities) ->
void override;
Definition: detection_sensor.hpp:37
auto isOnOrAboveEgoPlane(const geometry_msgs::Pose &npc_pose, const geometry_msgs::Pose &ego_pose) -> bool
Definition: detection_sensor.cpp:69
DetectionSensorBase(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration)
Definition: detection_sensor.hpp:43
virtual ~DetectionSensorBase()=default
simulation_api_schema::DetectionSensorConfiguration configuration_
Definition: detection_sensor.hpp:41
auto isEgoEntityStatusToWhichThisSensorIsAttached(const traffic_simulator_msgs::EntityStatus &) const -> bool
Definition: detection_sensor.cpp:46
double previous_simulation_time_
Definition: detection_sensor.hpp:39
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:53
Definition: detection_sensor.hpp:75
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:162
~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: autoware_universe.hpp:40
auto getParameter(const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node, const std::string &name, T value={})
Definition: get_parameter.hpp:25
Definition: constants.hpp:19
Definition: lanelet_wrapper.hpp:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32
Definition: exception.hpp:27