#[repr(C)]pub struct LaserScan {
pub header: Header,
pub angle_min: f32,
pub angle_max: f32,
pub angle_increment: f32,
pub time_increments: f32,
pub scan_time: f32,
pub range_min: f32,
pub range_max: f32,
pub ranges: Vec<f32>,
pub intensities: Vec<f32>,
}
Fields§
§header: Header
timestamp in the header is the acquisition time of the first ray in the scan.
in frame frame_id, angles are measured around the positive Z axis (counterclockwise, if Z is up) with zero angle being forward along the x axis
angle_min: f32
start angle of the scan in radians
angle_max: f32
end angle of the scan in radians
angle_increment: f32
angular distance between measurements
time_increments: f32
time between scans in seconds if your scanner is moving, this will be used in interpolating position of 3d points
scan_time: f32
time between scans in seconds
range_min: f32
minimum range value in metres
range_max: f32
maximum range valie in metres
ranges: Vec<f32>
range data in metres
intensities: Vec<f32>
intensity data
Implementations§
Source§impl LaserScan
impl LaserScan
Sourcepub fn create_topic_with_name(
participant: &DdsParticipant,
name: &str,
maybe_qos: Option<DdsQos>,
maybe_listener: Option<DdsListener>,
) -> Result<DdsTopic<Self>, DDSError>
pub fn create_topic_with_name( participant: &DdsParticipant, name: &str, maybe_qos: Option<DdsQos>, maybe_listener: Option<DdsListener>, ) -> Result<DdsTopic<Self>, DDSError>
Create a topic using of this Type specifying the topic name
§Arguments
participant
- The participant handle onto which this topic should be createdname
- The name of the topicmaybe_qos
- A QoS structure for this topic. The Qos is optionalmaybe_listener
- A listener to use on this topic. The listener is optional
Sourcepub fn create_topic(
participant: &DdsParticipant,
maybe_topic_prefix: Option<&str>,
maybe_qos: Option<DdsQos>,
maybe_listener: Option<DdsListener>,
) -> Result<DdsTopic<Self>, DDSError>
pub fn create_topic( participant: &DdsParticipant, maybe_topic_prefix: Option<&str>, maybe_qos: Option<DdsQos>, maybe_listener: Option<DdsListener>, ) -> Result<DdsTopic<Self>, DDSError>
Create a topic of this Type using the default topic name. The default topic name is provided by the Self::topic_name function.
§Arguments
participant
- The participant handle onto which this topic should be createdmaybe_topic_prefix
- An additional prefix to be added to the topic name. This can be Nonemaybe_qos
- A QoS structure for this topic. The Qos is optionalmaybe_listener
- A listener to use on this topic. The listener is optional
Sourcepub fn create_sample_buffer(len: usize) -> SampleBuffer<LaserScan>
pub fn create_sample_buffer(len: usize) -> SampleBuffer<LaserScan>
Create a sample buffer for storing an array of samples You can pass the sample buffer into a read to read multiple samples. Multiple samples are useful when you have one or more keys in your topic structure. Each value of the key will result in the storage of another sample.