Struct robotics_signals::sensors::point_cloud::PointCloud
source · [−]#[repr(C)]pub struct PointCloud {
pub header: Header,
pub height: u32,
pub width: u32,
pub fields: Vec<PointField>,
pub is_bigendian: bool,
pub point_step: u32,
pub row_step: u32,
pub data: Vec<u8>,
pub is_dense: bool,
}
Expand description
This message holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc. The point data is stored as a binary blob, its layout described by the contents of the “fields” array.
The point cloud data may be organized 2d (image-like) or 1d (unordered). Point clouds organized as 2d images may be produced by camera depth sensors such as stereo or time-of-flight.
Fields
header: Header
Time of sensor data acquisition, and the coordinate frame ID (for 3d points).
height: u32
2D structure of the point cloud. If the point cloud is unordered, height is 1 and width is the length of the point cloud.
width: u32
fields: Vec<PointField>
Describes the channels and their layout in the binary data blob.
is_bigendian: bool
point_step: u32
length of a point in bytes
row_step: u32
length of a row in bytes
data: Vec<u8>
Point data. size is (row_step*height)
is_dense: bool
true if there are no invalid points
Implementations
sourceimpl PointCloud
impl PointCloud
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<PointCloud>
pub fn create_sample_buffer(len: usize) -> SampleBuffer<PointCloud>
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.