#[repr(C)]
#[derive(Debug, ros2_types::Ros2Msg, ros2_types::TypeDescription)]
#[ros2(package = "sensor_msgs", interface_type = "msg")]
#[cfg_attr(
not(feature = "rcl"),
derive(ros2_types::serde::Serialize, ros2_types::serde::Deserialize)
)]
#[cfg_attr(not(feature = "rcl"), serde(crate = "ros2_types::serde"))]
pub struct LaserScan {
pub header: super::super::super::std_msgs::msg::header::Header,
pub angle_min: f32,
pub angle_max: f32,
pub angle_increment: f32,
pub time_increment: f32,
pub scan_time: f32,
pub range_min: f32,
pub range_max: f32,
pub ranges: crate::msg::F32Seq<0>,
pub intensities: crate::msg::F32Seq<0>,
}