scenario_simulator_v2 C++ API
detection_sensor.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__DETECTION_SENSOR__DETECTION_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__DETECTION_SENSOR__DETECTION_SENSOR_HPP_
17 
18 #include <simulation_api_schema.pb.h>
19 
20 #include <memory>
21 #include <queue>
22 #include <random>
23 #include <rclcpp/rclcpp.hpp>
24 #include <string>
25 #include <utility>
26 #include <vector>
27 
29 {
31 {
32 protected:
34 
35  simulation_api_schema::DetectionSensorConfiguration configuration_;
36 
38  const double current_simulation_time,
39  const simulation_api_schema::DetectionSensorConfiguration & configuration)
40  : previous_simulation_time_(current_simulation_time), configuration_(configuration)
41  {
42  }
43 
45  const traffic_simulator_msgs::EntityStatus &) const -> bool;
46 
48  const std::vector<traffic_simulator_msgs::EntityStatus> &) const
49  -> std::vector<traffic_simulator_msgs::EntityStatus>::const_iterator;
50 
51 public:
52  virtual ~DetectionSensorBase() = default;
53 
54  virtual void update(
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;
58 };
59 
60 template <typename T, typename U = autoware_auto_perception_msgs::msg::TrackedObjects>
62 {
63  const typename rclcpp::Publisher<T>::SharedPtr detected_objects_publisher;
64 
65  const typename rclcpp::Publisher<U>::SharedPtr ground_truth_objects_publisher;
66 
67  std::default_random_engine random_engine_;
68 
69  std::queue<std::pair<autoware_auto_perception_msgs::msg::DetectedObjects, double>>
70  detected_objects_queue;
71 
72  std::queue<std::pair<autoware_auto_perception_msgs::msg::TrackedObjects, double>>
73  ground_truth_objects_queue;
74 
75 public:
76  explicit DetectionSensor(
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)
81  : DetectionSensorBase(current_simulation_time, configuration),
82  detected_objects_publisher(publisher),
83  ground_truth_objects_publisher(ground_truth_publisher),
84  random_engine_(configuration.random_seed())
85  {
86  }
87 
88  ~DetectionSensor() override = default;
89 
90  auto update(
91  const double, const std::vector<traffic_simulator_msgs::EntityStatus> &, const rclcpp::Time &,
92  const std::vector<std::string> & lidar_detected_entities) -> void override;
93 };
94 } // namespace simple_sensor_simulator
95 
96 #endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__DETECTION_SENSOR__DETECTION_SENSOR_HPP_
Definition: detection_sensor.hpp:31
DetectionSensorBase(const double current_simulation_time, const simulation_api_schema::DetectionSensorConfiguration &configuration)
Definition: detection_sensor.hpp:37
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 &current_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
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::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:24