readFrame
Syntax
Description
reads the next point cloud frame from the Velodyne ROS messages and returns a
ptCloud
= readFrame(veloReader
)pointCloud
object. The next point cloud frame is the first point cloud
available at or after the value of the CurrentTime
property of the
Velodyne ROS message reader object veloReader
.
reads the point cloud with the specified frame number from the Velodyne ROS messages.ptCloud
= readFrame(veloReader
,frameNumber
)
reads the first point cloud available at or after the specified timestamp
ptCloud
= readFrame(veloReader
,frameTime
)frameTime
.
[
returns the timestamps for all points in the point cloud using any combination of input
arguments from previous syntaxes.ptCloud
,pointTimestamps
] = readFrame(___)
Examples
Work with Velodyne ROS Messages
This example shows how to handle VelodyneScan
messages from a Velodyne LiDAR.
Velodyne ROS messages store data in a format that requires some interpretation before it can be used for further processing. MATLAB® can help you by formatting Velodyne ROS messages for easy use.
Prerequisites: Work with Basic ROS Messages
Load Sample Messages
Load sample Velodyne messages. These messages are populated with data gathered from Velodyne LiDAR sensor.
load("lidarData_ConstructionRoad.mat")
VelodyneScan Messages
VelodyneScan
messages are ROS messages that contain Velodyne LIDAR scan packets. You can see the standard ROS format for a VelodyneScan
message by creating an empty message of the appropriate type. Use messages in structure format for better performance.
emptyveloScan = rosmessage("velodyne_msgs/VelodyneScan","DataFormat","struct")
emptyveloScan = struct with fields:
MessageType: 'velodyne_msgs/VelodyneScan'
Header: [1×1 struct]
Packets: [0×1 struct]
Since you created an empty message, emptyveloScan
does not contain any meaningful data. For convenience, the loaded lidarData_ConstructionRoad.mat
file contains a set of VelodyneScan
messages that are fully populated and stored in the msgs
variable. Each element in the msgs
cell array is a VelodyneScan
ROS message struct. The primary data in each VelodyneScan
message is in the Packets
property, it contains multiple VelodynePacket
messages. You can see the standard ROS format for a VelodynePacket message by creating an empty message of the appropriate type.
emptyveloPkt = rosmessage("velodyne_msgs/VelodynePacket","DataFormat","struct")
emptyveloPkt = struct with fields:
MessageType: 'velodyne_msgs/VelodynePacket'
Stamp: [1×1 struct]
Data: [1206×1 uint8]
Create Velodyne ROS Message Reader
The velodyneROSMessageReader
object reads point cloud data from VelodyneScan
ROS messages based on their specified model type. Note that providing an incorrect device model may result in improperly calibrated point clouds. This example uses messages from the "HDL32E"
model.
veloReader = velodyneROSMessageReader(msgs,"HDL32E")
veloReader = velodyneROSMessageReader with properties: VelodyneMessages: {28×1 cell} DeviceModel: 'HDL32E' CalibrationFile: 'M:\jobarchive\Bdoc21b\2021_06_16_h16m50s15_job1697727_pass\matlab\toolbox\shared\pointclouds\utilities\velodyneFileReaderConfiguration\HDL32E.xml' NumberOfFrames: 55 Duration: 2.7477 sec StartTime: 1145.2 sec EndTime: 1147.9 sec Timestamps: [1145.2 sec 1145.2 sec 1145.3 sec 1145.3 sec 1145.4 sec 1145.4 sec 1145.5 sec 1145.5 sec 1145.6 sec 1145.6 sec 1145.7 sec 1145.7 sec 1145.8 sec 1145.8 sec 1145.9 sec 1145.9 sec … ] CurrentTime: 1145.2 sec
Extract Point Clouds
You can extract point clouds from the raw packets message with the help of this velodyneROSMessageReader
object. By providing a specific frame number or timestamp, one point cloud can be extracted from velodyneROSMessageReader
object using the readFrame
object function. If you call readFrame
without a frame number or timestamp, it extracts the next point cloud in the sequence based on the CurrentTime
property.
Create a duration scalar that represents one second after the first point cloud reading.
timeDuration = veloReader.StartTime + seconds(1);
Read the first point cloud recorded at or after the given time duration.
ptCloudObj = readFrame(veloReader,timeDuration);
Access Location
data in the point cloud.
ptCloudLoc = ptCloudObj.Location;
Reset the CurrentTime
property of veloReader
to the default value
reset(veloReader)
Display All Point Clouds
You can also loop through all point clouds in the input Velodyne ROS messages.
Define x-, y-, and z-axes limits for pcplayer
in meters. Label the axes.
xlimits = [-60 60]; ylimits = [-60 60]; zlimits = [-20 20];
Create the point cloud player.
player = pcplayer(xlimits,ylimits,zlimits);
Label the axes.
xlabel(player.Axes,"X (m)"); ylabel(player.Axes,"Y (m)"); zlabel(player.Axes,"Z (m)");
The first point cloud of interest is captured at 0.3 second into the input messages. Set the CurrentTime
property to that time to begin reading point clouds from there.
veloReader.CurrentTime = veloReader.StartTime + seconds(0.3);
Display the point cloud stream for 2 seconds. To check if a new frame is available and continue past 2 seconds, remove the last while
condition. Iterate through the file by calling readFrame
to read in point clouds. Display them using the point cloud player.
while(hasFrame(veloReader) && isOpen(player) && (veloReader.CurrentTime < veloReader.StartTime + seconds(2))) ptCloudObj = readFrame(veloReader); view(player,ptCloudObj.Location,ptCloudObj.Intensity); pause(0.1); end
Input Arguments
veloReader
— Velodyne ROS message reader
velodyneROSMesasgeReader
object
Velodyne ROS message reader, specified as a velodyneROSMessageReader
object.
frameNumber
— Frame number of desired point cloud
positive integer
Frame number of the desired point cloud, specified as a positive integer. Frame
numbers are sequential in the velodyneROSMessageReader
object.
frameTime
— Frame time of desired point cloud
duration
scalar
Frame time of the desired point cloud, specified as a duration
scalar in seconds. The function return the first frame available at
or after the specified timestamp.
Output Arguments
ptCloud
— Point Cloud
pointCloud
object
Point cloud, returned as pointCloud
object.
pointTimestamps
— Timestamps for all points in point cloud
duration
vector | duration
matrix
Timestamps for all points in the point cloud, returned as a duration
vector or a matrix.
The function returns timestamps as:
An M-element vector for unorganized point clouds. M is the total number of points in the point cloud.
An M-by-N matrix for organized point clouds. M and N are the number of rows and columns in the organized point cloud, respectively.
Timestamps are between the values of StartTime
and
EndTime
, which are properties of the velodyneROSMessageReader
object. Points in an organized point cloud with a
NaN
value is returned with a time stamp set to
NaN
.
Version History
Introduced in R2020b
See Also
MATLAB-Befehl
Sie haben auf einen Link geklickt, der diesem MATLAB-Befehl entspricht:
Führen Sie den Befehl durch Eingabe in das MATLAB-Befehlsfenster aus. Webbrowser unterstützen keine MATLAB-Befehle.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list:
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)