delete
Remove ros2bagwriter object from memory
Syntax
Description
delete(
removes the bagwriter
)ros2bagwriter
object
from memory. The function closes the opened ROS 2 bag file before deleting the
object.
If multiple references to the ros2bagwriter
object exist in the
workspace, deleting the ros2bagwriter
object invalidates the remaining
reference. Use the clear
command to delete the remaining references to
the object from the workspace.
Note
The ros2bagwriter
object locks the created bag file. Delete and
clear the ros2bagwriter
object to use the ROS 2 bag file.
Examples
Write Log Using ros2bagwriter
Object by Reading Messages from ROS 2 Bag File
Extract the zip file that contains the ROS 2 bag log file and specify the full path to the log folder.
unzip('ros2_netwrk_bag.zip'); folderPath = fullfile(pwd,'ros2_netwrk_bag');
Get all the information from the ROS 2 bag log file.
bag2info = ros2("bag","info",folderPath);
Create a ros2bagreader
object that contains all messages in the log file.
bag = ros2bagreader(folderPath); bag.AvailableTopics
ans=4×3 table
NumMessages MessageType MessageDefinition
___________ _____________________ ______________________________________________________________________________________________________
/clock 1.607e+05 rosgraph_msgs/Clock {'%...' }
/cmd_vel 3 geometry_msgs/Twist {'...' }
/odom 5275 nav_msgs/Odometry {'% The pose in this message should be specified in the coordinate frame given by header.frame_id...'}
/scan 892 sensor_msgs/LaserScan {'%...' }
Select a subset of the messages, by applying filters to the topic and timestamp.
start = bag.StartTime; odomBagSel = select(bag,"Time",[start start + 30e+09],"Topic","/odom")
odomBagSel = ros2bagreader with properties: FilePath: '/tmp/Bdoc22b_2134332_1954357/tpdf3c6620/ros-ex95368813/ros2_netwrk_bag/ros2_netwrk_bag.db3' StartTime: 1601984883976047597 EndTime: 1601984913775044431 AvailableTopics: [1x3 table] MessageList: [801x3 table] NumMessages: 801
Get the messages in the selection.
odomMsgs = readMessages(odomBagSel);
Retrieve the list of timestamps from the topic. Convert the list to values with the double
data type.
timestamps = odomBagSel.MessageList.Time; timestamps_double = num2cell(double(timestamps)/1e+09);
Create a ros2bagwriter
object and a ROS 2 bag file in the specified folder.
bagwriter = ros2bagwriter("myRos2bag");
Write the messages related to the topic '/odom
' to the ROS 2 bag file.
write(bagwriter,"/odom",timestamps_double,odomMsgs)
Close the bag file, remove the ros2bagwriter
object from memory, and clear the associated object.
delete(bagwriter)
clear bagwriter
Load the new ROS 2 bag log file.
bagOdom = ros2bagreader("myRos2bag");
Retrieve messages from the ROS 2 bag log file.
msgs = readMessages(bagOdom);
Plot the coordinates for the messages in the ROS 2 bag log file.
Remove the myRos2bag
file and the ros2_netwrk_bag
file from memory to run the example again.
plot(cellfun(@(msg) msg.pose.pose.position.x,msgs),cellfun(@(msg) msg.twist.twist.angular.z,msgs))
Create Single Log and Write to ROS 2 Bag File
Create a ros2bagwriter
object and a ROS 2 bag file in the specified folder.
bagwriter = ros2bagwriter("myRos2bag");
Write a single log to the ROS 2 bag file.
topic = "/odom"; message = ros2message("nav_msgs/Odometry"); timestamp = ros2time(1.6170e+09); write(bagwriter,topic,timestamp,message)
Close the bag file, remove the ros2bagwriter
object from memory, and clear the associated object.
delete(bagwriter)
clear bagwriter
Create Multiple Logs and Write to ROS 2 Bag File
Create a ros2bagwriter
object and a ROS 2 bag file in the specified folder. Specify the cache size for each message.
bagwriter = ros2bagwriter("bag_files/my_bag_file",CacheSize=1500);
Write multiple logs to the ROS 2 bag file.
message1 = ros2message("nav_msgs/Odometry"); message2 = ros2message("geometry_msgs/Twist"); message3 = ros2message("sensor_msgs/Image"); write(bagwriter, ... ["/odom","cmd_vel","/camera/rgb/image_raw"], ... {ros2time(1.6160e+09),ros2time(1.6170e+09),ros2time(1.6180e+09)}, ... {message1,message2,message3})
Close the bag file, remove the ros2bagwriter
object from memory, and clear the associated object.
delete(bagwriter)
clear bagwriter
Create Multiple Logs for Same Topic and Write to ROS 2 Bag File
Create a ros2bagwriter
object and a ROS 2 bag file in the specified folder.
bagwriter = ros2bagwriter("myBag");
Write multiple logs for the same topic to the ROS 2 bag file.
pointMsg1 = ros2message("geometry_msgs/Point"); pointMsg1.x = 1; pointMsg2 = ros2message("geometry_msgs/Point"); pointMsg2.x = 2; pointMsg3 = ros2message("geometry_msgs/Point"); pointMsg3.x = 3; write(bagwriter, ... "/point", ... {1.6190e+09, 1.6200e+09,1.6210e+09}, ... {pointMsg1,pointMsg2,pointMsg3})
Close the bag file, remove the ros2bagwriter
object from memory, and clear the associated object.
delete(bagwriter)
clear bagwriter
Input Arguments
bagwriter
— ROS 2 log file writer
ros2bagwriter
object
ROS 2 log file writer, specified as a ros2bagwriter
object.
Version History
Introduced in R2022b
Apri esempio
Si dispone di una versione modificata di questo esempio. Desideri aprire questo esempio con le tue modifiche?
Comando MATLAB
Hai fatto clic su un collegamento che corrisponde a questo comando MATLAB:
Esegui il comando inserendolo nella finestra di comando MATLAB. I browser web non supportano i comandi MATLAB.
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)