15 #ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__LIDAR__LIDAR_SENSOR_HPP_ 
   16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__LIDAR__LIDAR_SENSOR_HPP_ 
   18 #include <simulation_interface/simulation_api_schema.pb.h> 
   20 #include <agnocast_wrapper/agnocast_wrapper.hpp> 
   22 #include <rclcpp/rclcpp.hpp> 
   23 #include <sensor_msgs/msg/point_cloud2.hpp> 
   41     const double current_simulation_time,
 
   42     const simulation_api_schema::LidarConfiguration & configuration)
 
   51     const double current_simulation_time, 
const std::vector<traffic_simulator_msgs::EntityStatus> &,
 
   52     const rclcpp::Time & current_ros_time) -> 
void = 0;
 
   60   const agnocast_wrapper::PublisherPtr<T> publisher_ptr_;
 
   62   std::queue<std::pair<sensor_msgs::msg::PointCloud2, double>> queue_pointcloud_;
 
   64   auto raycast(
const std::vector<traffic_simulator_msgs::EntityStatus> &, 
const rclcpp::Time &)
 
   69     const double current_simulation_time,
 
   70     const simulation_api_schema::LidarConfiguration & configuration,
 
   71     const agnocast_wrapper::PublisherPtr<T> & publisher_ptr)
 
   72   : 
LidarSensorBase(current_simulation_time, configuration), publisher_ptr_(publisher_ptr)
 
   78     const double current_simulation_time,
 
   79     const std::vector<traffic_simulator_msgs::EntityStatus> & status,
 
   80     const rclcpp::Time & current_ros_time) -> 
void override 
   86       queue_pointcloud_.push(
 
   87         std::make_pair(raycast(status, current_ros_time), current_simulation_time));
 
   93       not queue_pointcloud_.empty() and
 
   94       current_simulation_time - queue_pointcloud_.front().second >=
 
   96       auto pointcloud = agnocast_wrapper::create_message(publisher_ptr_);
 
   97       *pointcloud = queue_pointcloud_.front().first;
 
   98       queue_pointcloud_.pop();
 
   99       publisher_ptr_->publish(std::move(pointcloud));
 
  109 auto LidarSensor<sensor_msgs::msg::PointCloud2>::raycast(
 
  110   const std::vector<traffic_simulator_msgs::EntityStatus> &, 
const rclcpp::Time &)
 
  111   -> sensor_msgs::msg::PointCloud2;
 
Definition: lidar_sensor.hpp:31
LidarSensorBase(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration)
Definition: lidar_sensor.hpp:40
std::set< std::string > detected_objects_
Definition: lidar_sensor.hpp:38
Raycaster raycaster_
Definition: lidar_sensor.hpp:37
virtual auto update(const double current_simulation_time, const std::vector< traffic_simulator_msgs::EntityStatus > &, const rclcpp::Time ¤t_ros_time) -> void=0
virtual ~LidarSensorBase()=default
simulation_api_schema::LidarConfiguration configuration_
Definition: lidar_sensor.hpp:35
auto getDetectedObjects() const -> const std::set< std::string > &
Definition: lidar_sensor.hpp:54
double previous_simulation_time_
Definition: lidar_sensor.hpp:33
Definition: lidar_sensor.hpp:59
auto update(const double current_simulation_time, const std::vector< traffic_simulator_msgs::EntityStatus > &status, const rclcpp::Time ¤t_ros_time) -> void override
Definition: lidar_sensor.hpp:77
LidarSensor(const double current_simulation_time, const simulation_api_schema::LidarConfiguration &configuration, const agnocast_wrapper::PublisherPtr< T > &publisher_ptr)
Definition: lidar_sensor.hpp:68
Definition: raycaster.hpp:36
void setDirection(const simulation_api_schema::LidarConfiguration &configuration, double horizontal_angle_start=0, double horizontal_angle_end=2 *M_PI)
Definition: raycaster.cpp:61
Definition: constants.hpp:19
Definition: lanelet_wrapper.hpp:40