scenario_simulator_v2 C++ API
lidar_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__LIDAR__LIDAR_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__LIDAR__LIDAR_SENSOR_HPP_
17 
18 #include <simulation_api_schema.pb.h>
19 
21 #include <memory>
22 #include <queue>
23 #include <rclcpp/rclcpp.hpp>
24 #include <sensor_msgs/msg/point_cloud2.hpp>
26 #include <string>
27 #include <vector>
28 
30 {
32 {
33 protected:
35 
36  simulation_api_schema::LidarConfiguration configuration_;
37 
39  std::vector<std::string> detected_objects_;
40 
41  explicit LidarSensorBase(
42  const double current_simulation_time,
43  const simulation_api_schema::LidarConfiguration & configuration)
44  : previous_simulation_time_(current_simulation_time), configuration_(configuration)
45  {
46  }
47 
48 public:
49  virtual ~LidarSensorBase() = default;
50 
51  virtual auto update(
52  const double current_simulation_time, const std::vector<traffic_simulator_msgs::EntityStatus> &,
53  const rclcpp::Time & current_ros_time) -> void = 0;
54 
55  auto getDetectedObjects() const -> const std::vector<std::string> & { return detected_objects_; }
56 };
57 
58 template <typename T>
60 {
61  const typename rclcpp::Publisher<T>::SharedPtr publisher_ptr_;
62 
63  std::queue<std::pair<sensor_msgs::msg::PointCloud2, double>> queue_pointcloud_;
64 
65  auto raycast(const std::vector<traffic_simulator_msgs::EntityStatus> &, const rclcpp::Time &)
66  -> T;
67 
68 public:
69  explicit LidarSensor(
70  const double current_simulation_time,
71  const simulation_api_schema::LidarConfiguration & configuration,
72  const typename rclcpp::Publisher<T>::SharedPtr & publisher_ptr)
73  : LidarSensorBase(current_simulation_time, configuration), publisher_ptr_(publisher_ptr)
74  {
75  raycaster_.setDirection(configuration);
76  }
77 
78  auto update(
79  const double current_simulation_time,
80  const std::vector<traffic_simulator_msgs::EntityStatus> & status,
81  const rclcpp::Time & current_ros_time) -> void override
82  {
83  if (
84  current_simulation_time - previous_simulation_time_ - configuration_.scan_duration() >=
85  -0.002) {
86  previous_simulation_time_ = current_simulation_time;
87  queue_pointcloud_.push(
88  std::make_pair(raycast(status, current_ros_time), current_simulation_time));
89  } else {
90  detected_objects_.clear();
91  }
92 
93  if (
94  not queue_pointcloud_.empty() and
95  current_simulation_time - queue_pointcloud_.front().second >=
96  configuration_.lidar_sensor_delay()) {
97  const auto pointcloud = queue_pointcloud_.front().first;
98  queue_pointcloud_.pop();
99  publisher_ptr_->publish(pointcloud);
100  }
101  }
102 
103 private:
104  // Override
105  Raycaster raycaster_;
106 };
107 
108 template <>
109 auto LidarSensor<sensor_msgs::msg::PointCloud2>::raycast(
110  const std::vector<traffic_simulator_msgs::EntityStatus> &, const rclcpp::Time &)
111  -> sensor_msgs::msg::PointCloud2;
112 } // namespace simple_sensor_simulator
113 
114 #endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__LIDAR__LIDAR_SENSOR_HPP_
Definition: lidar_sensor.hpp:32
LidarSensorBase(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration)
Definition: lidar_sensor.hpp:41
std::vector< std::string > detected_objects_
Definition: lidar_sensor.hpp:39
Raycaster raycaster_
Definition: lidar_sensor.hpp:38
virtual auto update(const double current_simulation_time, const std::vector< traffic_simulator_msgs::EntityStatus > &, const rclcpp::Time &current_ros_time) -> void=0
auto getDetectedObjects() const -> const std::vector< std::string > &
Definition: lidar_sensor.hpp:55
simulation_api_schema::LidarConfiguration configuration_
Definition: lidar_sensor.hpp:36
double previous_simulation_time_
Definition: lidar_sensor.hpp:34
Definition: lidar_sensor.hpp:60
LidarSensor(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration, const typename rclcpp::Publisher< T >::SharedPtr &publisher_ptr)
Definition: lidar_sensor.hpp:69
auto update(const double current_simulation_time, const std::vector< traffic_simulator_msgs::EntityStatus > &status, const rclcpp::Time &current_ros_time) -> void override
Definition: lidar_sensor.hpp:78
Definition: raycaster.hpp:38
void setDirection(const simulation_api_schema::LidarConfiguration &configuration, double horizontal_angle_start=0, double horizontal_angle_end=2 *M_PI)
Definition: raycaster.cpp:48
Definition: constants.hpp:19
Definition: cache.hpp:27