Main Content

Use ROS 2 Logger App to Save ROS 2 Messages from Simulink

Use ROS 2 Logger app to record ROS 2 messages during Simulink® simulation, and obtain a ROS 2 bag file with fully synchronized ROS 2 messages saved during simulation.

In this example, you will

  • Load pre-defined 3D simulation environment provided by Automated Driving Toolbox(TM).

  • Configure ROS 2 message logging in ROS 2 Logger app.

  • Visualize logged ROS 2 messages.

Load 3D Simulation Environment

Use the prebuilt Large Parking Lot scene created using the Unreal Engine 3D simulation environment in Simulink. To interactively select a sequence of waypoints from a scene and generate a custom vehicle trajectory, refer to Select Waypoints for Unreal Engine Simulation (Automated Driving Toolbox) example.

% Extract scene for visualization
sceneName = 'LargeParkingLot';
[sceneImage, sceneRef] = helperGetSceneImage(sceneName);
hScene = figure;
helperShowSceneImage(sceneImage, sceneRef)
title(sceneName)

% Interactively Select Waypoints
hFig = helperSelectSceneWaypoints(sceneImage, sceneRef);

% Prepare smooth poses for simulation
if exist('refPoses','var')==0 || exist('wayPoints','var')==0
    % Load MAT-file containing preselected waypoints
    data = load('waypointsForROSLoggerAppParking');

    % Assign to caller workspace
    assignin('caller','wayPoints',data.wayPoints);
    assignin('caller','refPoses',data.refPoses);
end
numPoses = size(refPoses{1}, 1);

refDirections  = ones(numPoses,1);   % Forward-only motion
numSmoothPoses = 10 * numPoses;      % Increase this to increase the number of returned poses

[smoothRefPoses,~,cumLengths] = smoothPathSpline(refPoses{1}, refDirections, numSmoothPoses);

Configure ROS 2 Message Logging

Open the model.

modelName = 'LogROS2MessageFrom3DSimulation';
open_system(modelName);

To launch ROS 2 Logger app and configure saving options, click ROS Logger in Prepare section under Simulation. You can enable or disable ROS 2 messages for saving, define custom file name, and rename messages saved to the ROS 2 bag file based on your preference.

After configuring with ROS 2 Logger app, run these commands to setup model parameters and run the simulation.

% Configure the model to stop simulation at 5 seconds.
simStopTime = 5;
set_param(gcs, 'StopTime', num2str(simStopTime));

% Create a constant velocity profile by generating a time vector
% proportional to the cumulative path length.
timeVector = normalize(cumLengths, 'range', [0, simStopTime]);

% Create variables required by the Simulink model.
refPosesX = [timeVector, smoothRefPoses(:,1)];
refPosesY = [timeVector, smoothRefPoses(:,2)];
refPosesT = [timeVector, smoothRefPoses(:,3)];

% Run the simulation
sim(modelName);

After running the simulation, you can see a ROS 2 bag folder generated in your current working directory. Long running simulations take some time to generate ROS 2 bag files.

Visualize Logged ROS 2 Messages

Based on how you setup the "Folder name" in ROS 2 Logger app, the name of the ROS 2 bag folder would be different. In this section, we use folderpath to represent the path to the generated bag folder.

You can proceed to inspect the bag with "ros2("bag","info",folderpath)" after you see the message “Successfully logged ROS 2 bag file to…”.

You can inspect the saved PointCloud2 messages with this message.

bagReader = ros2bagreader(folderpath);
bagSel = select(bagReader,"Topic","/header_assignment1");
pointCloudMsgs = readMessages(bagSel);
ptCloudXYZ = rosReadXYZ(pointCloudMsgs{1,1});
player = pcplayer([-50 100],[-50 100],[-50 100]);
ptCloud = pointCloud(ptCloudXYZ);
view(player,ptCloud);

Untitled.png

You can also inspect the saved Image messages with this message.

bagReader = ros2bagreader(folderpath);
bagSel = select(bagReader,"Topic","/header_assignment");
imgMsgs = readMessages(bagSel);
img = rosReadImage(imgMsgs{201,1});
imshow(img)

Untitled1.png

Close the Simulink model and all the windows.

close(hFig)
close_system(modelName, 0)
close(hScene)