ousterROSMessageReader
Description
The ousterROSMessageReader
object reads the point cloud data
from PacketMsg
ROS messages, collected from a Ouster® lidar sensor. To read this point cloud data into the workspace as point cloud
object, use the object function readFrame
. To check
for additional point clouds in the message set, use the object function hasFrame
.
Creation
Syntax
Description
creates a Ouster ROS message reader object for a set of ousterReader
= ousterROSMessageReader(msgs
,calibrationFile
)PacketMsg
ROS
messages msgs
created from raw Ouster lidar data messages in a specified calibration JSON file
calibrationFile
.
specifies options using one or more name-value arguments in addition to any combination
of arguments from previous syntaxes. ousterReader
= ousterROSMessageReader(msgs
,calibrationFile
,Name=Value
)
Input Arguments
msgs
— ROS Ouster scan messages
cell array of PacketMsg
message objects | structure array
Ouster scan ROS messages, specified as a cell array of
PacketMsg
message objects or a structure array. The message type
is ouster_ros/PacketMsg
. This argument sets the
OusterMessages
property.
calibrationFile
— Calibration JSON file
""
(default) | string
Calibration JSON file, specified as a string.
A calibration file for Ouster lidar data holds crucial parameters and adjustment values utilized to convert initial sensor readings into precise 3D point cloud data. This file plays a vital role in the data processing sequence, guaranteeing that the lidar data is appropriately modified and matched to real-world coordinates.
If you do not specify a calibration file, the reader selects a default calibration file containing data from the Ouster device manual.
Specify optional pairs of arguments as
Name1=Value1,...,NameN=ValueN
, where Name
is
the argument name and Value
is the corresponding value.
Name-value arguments must appear after other arguments, but the order of the
pairs does not matter.
Before R2021a, use commas to separate each name and value, and enclose
Name
in quotes.
Example: (SkipPartialFrames
=true
) returns an
Ouster file reader that skips partial frames from the set of
PacketMsg
ROS messages.
SkipPartialFrames
— Logical for partial frame processing
true
or 1
(default) | false
or 0
Partial frame processing, specified as a numeric or logical1
(true
) or 0
(false
). Set
this property to true
to skip partial frames from the set of
PacketMsg
ROS messages.
Partial frames refer to frames that have a horizontal field of view smaller than the average horizontal field of view of all frames within the ROS Messages.
Example: ousterFileReader(fileName,calibrationFile,SkipPartialFrames=false)
creates an Ouster file reader that does not skip partial frames.
Data Types: logical
| numeric
CoordinateFrame
— Coordinate frame for point cloud data
"center"
(default) | "base"
Coordinate frame for point cloud data, specified as one of these options:
"center"
– Origin of the coordinate frame is at the center of the sensor."base"
– Origin of the coordinate frame is at the base of the sensor.
Example: ousterFileReader(fileName,calibrationFile,CoordinateFrame="center")
sets the origin of the coordinate frame at the center of the sensor.
Properties
OusterMessages
— Raw Ouster ROS messages
cell array of PacketMsg
message objects | structure array
This property is read-only.
Raw Ouster ROS messages, specified as a cell array of VelodyneScan message objects or
structure array. The ROS messages are of type
ouster_ros/PacketMsg
.
Data Types: struct
| cell array
calibrationFile
— Name of Ouster calibration JSON file
""
(default) | string
This property is read-only.
Name of Ouster calibration JSON file, specified as a string.
If you do not specify a calibration file, the reader selects a default calibration file containing data from the Ouster device manual.
Data Types: string
NumberOfFrames
— Number of point cloud frames
positive integer
This property is read-only.
Number of point cloud frames in the file, specified as a positive integer.
Data Types: double
Duration
— Total duration of bag messages in seconds
duration
scalar
This property is read-only.
Total duration of the bag messages, specified as a duration
scalar, in seconds.
StartTime
— Timestamp of first point cloud reading
duration
scalar
This property is read-only.
Timestamp of the first point cloud, specified as a duration
scalar in seconds.
Start and end times are specified relative to the previous whole hour. For instance, if the file is recorded for 7 minutes from 13:58 to 14:05, then:
StartTime
= 58 min = 3480 sEndTime
=StartTime
+ 7 min = 65 min = 3900 s
EndTime
— Timestamp of last point cloud reading
duration
scalar
This property is read-only.
Timestamp of the last point cloud reading, specified as a duration
scalar, in seconds.
Start and end times are relative to the whole hour. For example, if the data is recorded over the 7 minutes from 1:58 PM to 2:05 PM, then:
StartTime
= 58 min = 3840 sEndTime
=StartTime
+ 7 min = 65 min = 3900 s
Timestamps
— Timestamp of point cloud frames
duration
vector
This property is read-only.
Timestamps of the point cloud frames in seconds, specified as a duration
vector, representing the capture start time of all frames. The
length of the vector is equal to the value of the NumberOfFrames
property. The value of the first element in the vector is the same as that of the
StartTime
property. You can use this property to read point cloud
frames captured at different times.
For example, read the timestamp of a point cloud frame from the
Timestamps
property. Use the start time as an input for the
readFrame
object function to read the corresponding point cloud
frame.
ousterReader = ousterROSMessageReader(msgs,'')
frameTime = ousterReader.Timestamps(10);
ptCloud = readFrame(ousterReader,frameTime);
CurrentTime
— Timestamp of current point cloud
duration
scalar
Timestamp of the current point cloud reading, specified as a duration
scalar, in seconds. As you read point clouds using the readFrame
object function, the object updates this property with the most recently read point
cloud. You can use the reset
object
function to reset this property to the default value. The default value matches the
StartTime
property.
Object Functions
Examples
Work with Ouster ROS Messages to Visualize Point Cloud Data from Road Intersection
This example shows how to handle Ouster ROS messages from an Ouster® lidar sensor to visualize point cloud data from road intersection.
Ouster 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 Ouster ROS messages for easy use.
Download lidar capture data of road intersection from MathWorks® Supportfiles site.
httpsUrl = "https://ssd.mathworks.com"; dataUrl = strcat(httpsUrl,"/supportfiles/spc/ROS/ROS_Ouster_Supportfiles.zip"); dataFile = "ROS_Ouster_Supportfiles.zip"; lidarData = websave(dataFile,dataUrl);
Extract the ZIP file that contains lidar capture data of road intersection.
unzip("ROS_Ouster_Supportfiles.zip")
Load the ROS bag file to retrieve information from it.
bag = rosbag("lidar_capture_of_road_intersection.bag");
Create a BagSelection
object that contains the Ouster messages filtered by the topic /os_node/lidar_packets
.
bSel = select(bag,"Topic","/os_node/lidar_packets");
Read the messages from the selection. Each element in the msgs
cell array is an Ouster ROS message struct
. Using messages in structure format supports better performance.
msgs = readMessages(bSel, DataFormat="struct");
Create Ouster ROS Message Reader
The ousterROSMessageReader
object reads point cloud data from ouster_ros/PacketMsg
ROS messages, collected from an Ouster lidar sensor.
ousterReader = ousterROSMessageReader(msgs,"lidar_capture_of_road_intersection.json")
ousterReader = ousterROSMessageReader with properties: OusterMessages: {45342×1 cell} CalibrationFile: 'C:\Users\echakrab\OneDrive - MathWorks\Documents\MATLAB\ExampleManager\echakrab.myBdoc\ros-ex32591831\lidar_capture_of_road_intersection.json' NumberOfFrames: 709 Duration: 70.89 sec StartTime: 3539.2 sec EndTime: 3610.1 sec Timestamps: [3539.2 sec 3539.3 sec 3539.4 sec 3539.5 sec 3539.6 sec 3539.7 sec 3539.8 sec 3539.9 sec 3540 sec 3540.1 sec 3540.2 sec 3540.3 sec 3540.4 sec 3540.5 sec 3540.6 sec … ] (1×709 duration) CurrentTime: 3539.2 sec
Extract Point Clouds
You can extract point clouds from the raw packets message with the help of this ousterROSMessageReader
object. By providing a specific frame number or timestamp, one point cloud can be extracted from ousterROSMessageReader
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 = ousterReader.StartTime + seconds(1);
Read the first point cloud recorded at or after the given time duration.
ptCloudObj = readFrame(ousterReader,timeDuration);
Access Location
data in the point cloud.
ptCloudLoc = ptCloudObj.Location;
Reset the CurrentTime
property of ousterReader
to the default value.
reset(ousterReader)
Display Point Clouds
You can also loop through all point clouds in the input Ouster 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 and label the axes.
player = pcplayer(xlimits,ylimits,zlimits); 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.
ousterReader.CurrentTime = ousterReader.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(ousterReader) && isOpen(player)) && (ousterReader.CurrentTime < ousterReader.StartTime + seconds(2)) ptCloudObj = readFrame(ousterReader); view(player,ptCloudObj.Location,ptCloudObj.Intensity); pause(0.1); end
Reset the CurrentTime
property of the reader object to the default value.
reset(ousterReader)
Version History
Introduced in R2024a
See Also
pointCloud
| hasFrame
| readFrame
| reset
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
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)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)