ros2_interfaces_humble/sensor_msgs/msg/
laser_scan.rs1use serde::{Deserialize, Serialize};
2
3#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
4pub struct LaserScan {
5 pub header: crate::std_msgs::msg::Header,
6 pub angle_min: f32,
7 pub angle_max: f32,
8 pub angle_increment: f32,
9 pub time_increment: f32,
10 pub scan_time: f32,
11 pub range_min: f32,
12 pub range_max: f32,
13 pub ranges: Vec<f32>,
14 pub intensities: Vec<f32>,
15}
16
17impl Default for LaserScan {
18 fn default() -> Self {
19 LaserScan {
20 header: crate::std_msgs::msg::Header::default(),
21 angle_min: 0.0,
22 angle_max: 0.0,
23 angle_increment: 0.0,
24 time_increment: 0.0,
25 scan_time: 0.0,
26 range_min: 0.0,
27 range_max: 0.0,
28 ranges: Vec::new(),
29 intensities: Vec::new(),
30 }
31 }
32}
33
34impl ros2_client::Message for LaserScan {}