resumeRecording
Description
resumeRecording( continues
recording messages from ROS 2 topics after a paused session. The recorder resumes capturing
new incoming messages and writing them to the bag file, allowing the session to pick up
where it left off without creating a new file or reinitializing the writer.bagrecorder)
Examples
Start, pause, resume, and stop a recording session dynamically while messages are being published from multiple data sources. The publishing continues uninterrupted, and you can control recording manually or based on external conditions.
Create a node for a vehicle system that publishes telemetry, camera, and lidar data.
vehicleNode = ros2node('/VehicleNode'); telemetryPub = ros2publisher(vehicleNode,'/car_telemetry','std_msgs/String'); cameraPub = ros2publisher(vehicleNode,'/car_camera_feed','sensor_msgs/Image'); temperaturePub = ros2publisher(vehicleNode,'/temperature','sensor_msgs/Temperature');
By default, the recorder captures all topics. In this example, you record topics using IncludeRegex and ExcludeTopics filters. It includes all topics matching /car* but excludes the back camera feed.
bagName = "DynamicRecordingBag" + string(datetime("now",Format="_yyyyMMdd_HHmmss")); recorder = ros2bagrecorder(bagName); startRecording(recorder,IncludeRegex='/car*',ExcludeTopics='/car_camera_feed'); disp("Recording started.");
Recording started.
Set up message structures for telemetry, camera, and temperature data.
% Set up for callback structure pubStruct.telemetryPub = telemetryPub; pubStruct.cameraPub = cameraPub; pubStruct.temperaturePub = temperaturePub; % Set up for sample image message structure telemetryMsg = ros2message(telemetryPub); temperatureMsg = ros2message(temperaturePub); imageMsg = ros2message(cameraPub); imageMsg.height = uint32(480); imageMsg.width = uint32(640); imageMsg.step = uint32(imageMsg.width * 3); imageMsg.encoding = 'rgb8'; pubStruct.telemetryMsg = telemetryMsg; pubStruct.imageMsg = imageMsg; pubStruct.temperatureMsg = temperatureMsg;
Publishing continues regardless of the recording state. The callback function sends telemetry, camera, and temperature messages at regular intervals until all messages are published or the script ends.
function publishCallback(timerObj, pubStruct) idx = timerObj.UserData.idx; totalMsgs = timerObj.UserData.totalMsgs; if idx <= totalMsgs % Telemetry pubStruct.telemetryMsg.data = sprintf('Telemetry data message %d', idx); send(pubStruct.telemetryPub, pubStruct.telemetryMsg); % Back Camera pubStruct.imageMsg.data = randi([0 255], pubStruct.imageMsg.height, pubStruct.imageMsg.width, 3, 'uint8'); send(pubStruct.cameraPub, pubStruct.imageMsg); % Temperature pubStruct.temperatureMsg.temperature = randi([0 100]); send(pubStruct.temperaturePub, pubStruct.temperatureMsg); timerObj.UserData.idx = idx + 1; else stop(timerObj); end end
Create and start a timer to publish messages at a fixed rate.
timerObj = timer('ExecutionMode','fixedRate','Period',0.5,... 'TimerFcn', @(timerObj,~)publishCallback(timerObj,pubStruct)); timerObj.UserData.idx = 1; timerObj.UserData.totalMsgs = 2000; start(timerObj);
You can pause, resume, or stop recording manually at any time or based on external conditions. These options enable you to control the recording during a live session.
pauseRecording(recorder);
disp("Paused recording");Paused recording
resumeRecording(recorder);
disp("Resumed recording");Resumed recording
stopRecording(recorder);
disp("Recording stopped.")Recording stopped.
After stopping the recording, inspect the recorded topics and message types.
bagReader = ros2bagreader(bagName); disp(bagReader.AvailableTopics(:,1:2))
NumMessages MessageType
___________ _______________
/car_telemetry 1 std_msgs/String
You can see that messages published when the recording was active are stored in the bag file, while those published when the recording was paused are not recorded.
Input Arguments
ROS 2 bag recorder, specified as a ros2bagrecorder
object.
Version History
Introduced in R2026a
See Also
ros2bagrecorder | startRecording | pauseRecording | stopRecording
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.
Seleccione un país/idioma
Seleccione un país/idioma para obtener contenido traducido, si está disponible, y ver eventos y ofertas de productos y servicios locales. Según su ubicación geográfica, recomendamos que seleccione: .
También puede seleccionar uno de estos países/idiomas:
Cómo obtener el mejor rendimiento
Seleccione China (en idioma chino o inglés) para obtener el mejor rendimiento. Los sitios web de otros países no están optimizados para ser accedidos desde su ubicación geográfica.
América
- América Latina (Español)
- Canada (English)
- United States (English)
Europa
- 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)