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_api_schema.pb.h>
23 #include <rclcpp/rclcpp.hpp>
24 #include <sensor_msgs/msg/point_cloud2.hpp>
42 const double current_simulation_time,
43 const simulation_api_schema::LidarConfiguration & configuration)
52 const double current_simulation_time,
const std::vector<traffic_simulator_msgs::EntityStatus> &,
53 const rclcpp::Time & current_ros_time) ->
void = 0;
61 const typename rclcpp::Publisher<T>::SharedPtr publisher_ptr_;
63 std::queue<std::pair<sensor_msgs::msg::PointCloud2, double>> queue_pointcloud_;
65 auto raycast(
const std::vector<traffic_simulator_msgs::EntityStatus> &,
const rclcpp::Time &)
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)
79 const double current_simulation_time,
80 const std::vector<traffic_simulator_msgs::EntityStatus> & status,
81 const rclcpp::Time & current_ros_time) ->
void override
87 queue_pointcloud_.push(
88 std::make_pair(raycast(status, current_ros_time), current_simulation_time));
94 not queue_pointcloud_.empty() and
95 current_simulation_time - queue_pointcloud_.front().second >=
97 const auto pointcloud = queue_pointcloud_.front().first;
98 queue_pointcloud_.pop();
99 publisher_ptr_->publish(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: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 ¤t_ros_time) -> void=0
auto getDetectedObjects() const -> const std::vector< std::string > &
Definition: lidar_sensor.hpp:55
virtual ~LidarSensorBase()=default
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 ¤t_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