Extracting data with the MATLAB Robotics System Toolbox![Conflict Detection Enabled Conflict Detection Enabled](/sites/all/themes/redux/css/images/icons/conflict_enabled_icon.png)
The goal of this tutorial is to demonstrate how to visualize data in MATLAB, and analyze it for its conformance to design specification. The approach requires use of the Robotics System Toolbox from MathWorks (see http://www.mathworks.com/help/robotics/index.html for more information).
Overview
The Robotics System Toolbox provides a MATLAB interface to data from ROS, and can be used to plot data in real time, or to publish to a topic from a MATLAB .m file or a Simulink model. Since ROS as a middleware is effective at sending messages as data strings, the Robotics System Toolbox permits an efficient way in which to transform ROS data into data that are easily evaluated in MATLAB's tool suites.
Start up roscore
MATLAB can run roscore on its own, but there is no need to do this if you are already running roscore. I recommended running it in its own tab, in order to make it so the tutorial can be performed in many different scenarios.
$ roscoreIt is worth noting that if you want to only plot data files, then roscore need not be running. Any time you want to publish data from MATLAB, however, you will need it. Further, you can do a significant amount of data analysis without ROS installed, if you are just using MATLAB's ability to transform data from the bagfile.
Investigate a bagfile
The easiest way to get started is to find a bagfile and look to see what is inside. Let's do this with the rosbag utility first.
path: azcar_tutorial.bag
version: 2.0
duration: 2:14s (134s)
start: Dec 31 1969 16:45:13.84 (2713.84)
end: Dec 31 1969 16:47:28.49 (2848.49)
size: 1.1 GB
messages: 1036165
compression: none [1528/1528 chunks]
types: dynamic_reconfigure/Config [958f16a05573709014982821e6822580]
dynamic_reconfigure/ConfigDescription [757ce9d44ba8ddd801bb30bc456f946f]
gazebo_msgs/LinkStates [48c080191eb15c41858319b4d8a609c2]
gazebo_msgs/ModelStates [48c080191eb15c41858319b4d8a609c2]
geometry_msgs/Twist [9f195f881246fdfa2798d1d3eebca84a]
geometry_msgs/Wrench [4f539cf138b23283b520fd271b567936]
nav_msgs/Odometry [cd5e73d190d741a2f92e81eda573aca7]
nav_msgs/Path [6227e2b7e9cce15051f669a5e197bbf7]
rosgraph_msgs/Clock [a9c97c1d230cfc112e270351a944ee47]
rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb]
sensor_msgs/JointState [3066dcd76a6cfaef579bd0f34173e9fd]
sensor_msgs/LaserScan [90c7ef2dc6895d81024acba2ac42f369]
sensor_msgs/PointCloud [d8e9c3f5afbdd8a130fd1d2763945fca]
std_msgs/Float32 [73fcbf46b49191e672908e50842a83d4]
std_msgs/Float64 [fdb28210bfa9d7c91146260178d9a584]
tf2_msgs/TFMessage [94810edda583a504dfda3829e70d7eec]
visualization_msgs/InteractiveMarkerPose [a6e6833209a196a38d798dadb02c81f8]
topics: /azcar_sim/cmd_vel 2256 msgs : geometry_msgs/Twist
/azcar_sim/cmd_vel_safe 14645 msgs : geometry_msgs/Twist
/azcar_sim/distanceEstimator/angle 673 msgs : std_msgs/Float32
/azcar_sim/distanceEstimator/dist 673 msgs : std_msgs/Float32
/azcar_sim/front_laser_points 672 msgs : sensor_msgs/LaserScan
/azcar_sim/front_left_steering_position_controller/command 13446 msgs : std_msgs/Float64
/azcar_sim/front_right_steering_position_controller/command 13434 msgs : std_msgs/Float64
/azcar_sim/joint1_velocity_controller/command 13444 msgs : std_msgs/Float64
/azcar_sim/joint2_velocity_controller/command 13436 msgs : std_msgs/Float64
/azcar_sim/joint_states 14815 msgs : sensor_msgs/JointState (2 connections)
/azcar_sim/lidar_points 672 msgs : sensor_msgs/PointCloud
/azcar_sim/odom 125316 msgs : nav_msgs/Odometry
/azcar_sim/path 1347 msgs : nav_msgs/Path
/azcar_sim/steering 125393 msgs : geometry_msgs/Wrench
/azcar_sim/vel 125533 msgs : geometry_msgs/Twist
/azcar_sim/waypoint 2254 msgs : visualization_msgs/InteractiveMarkerPose
/clock 134461 msgs : rosgraph_msgs/Clock
/gazebo/link_states 134316 msgs : gazebo_msgs/LinkStates
/gazebo/model_states 134348 msgs : gazebo_msgs/ModelStates
/gazebo/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/gazebo/parameter_updates 1 msg : dynamic_reconfigure/Config
/rosout 25 msgs : rosgraph_msgs/Log (6 connections)
/rosout_agg 8 msgs : rosgraph_msgs/Log
/tf 164996 msgs : tf2_msgs/TFMessage (3 connections)
$
Let's look at the equivalent result from within MATLAB. First, navigate to the directory where you recorded those bagfiles, then:
>> bagfile
StartTime: 2.7138e+03
EndTime: 2.8485e+03
NumMessages: 1036165
AvailableTopics: [24x3 table]
MessageList: [1036165x4 table]
>>
To see the topics, let's look at the information in the structure
___________ ________________________________________ _________________________________________________________________________________________
/azcar_sim/cmd_vel_safe 14645 geometry_msgs/Twist '# This expresses velocity in free space broken into its linear and angular parts....'
/azcar_sim/distanceEstimator/angle 673 std_msgs/Float32 'float32 data...'
/azcar_sim/distanceEstimator/dist 673 std_msgs/Float32 'float32 data...'
/azcar_sim/front_laser_points 672 sensor_msgs/LaserScan '# Single scan from a planar laser range-finder...'
/azcar_sim/front_left_steering_position_controller/command 13446 std_msgs/Float64 'float64 data'
/azcar_sim/front_right_steering_position_controller/command 13434 std_msgs/Float64 'float64 data'
/azcar_sim/joint1_velocity_controller/command 13444 std_msgs/Float64 'float64 data'
/azcar_sim/joint2_velocity_controller/command 13436 std_msgs/Float64 'float64 data'
/azcar_sim/joint_states 14815 sensor_msgs/JointState '# This is a message that holds data to describe the state of a set of torque controlle...'
/azcar_sim/lidar_points 672 sensor_msgs/PointCloud '# This message holds a collection of 3d points, plus optional additional...'
/azcar_sim/odom 1.2532e+05 nav_msgs/Odometry '# This represents an estimate of a position and velocity in free space. ...'
/azcar_sim/path 1347 nav_msgs/Path '#An array of poses that represents a Path for a robot to follow...'
/azcar_sim/steering 1.2539e+05 geometry_msgs/Wrench '# This represents force in free space, separated into...'
/azcar_sim/vel 1.2553e+05 geometry_msgs/Twist '# This expresses velocity in free space broken into its linear and angular parts....'
/azcar_sim/waypoint 2254 visualization_msgs/InteractiveMarkerPose '# Time/frame info....'
/clock 1.3446e+05 rosgraph_msgs/Clock '# roslib/Clock is used for publishing simulated time in ROS. ...'
/gazebo/link_states 1.3432e+05 gazebo_msgs/LinkStates '# broadcast all link states in world frame...'
/gazebo/model_states 1.3435e+05 gazebo_msgs/ModelStates '# broadcast all model states in world frame...'
/gazebo/parameter_descriptions 1 dynamic_reconfigure/ConfigDescription 'Group[] groups...'
/gazebo/parameter_updates 1 dynamic_reconfigure/Config 'BoolParameter[] bools...'
/rosout 25 rosgraph_msgs/Log '##...'
/rosout_agg 8 rosgraph_msgs/Log '##...'
/tf 1.65e+05 tf2_msgs/TFMessage 'geometry_msgs/TransformStamped[] transforms...'
Ah, that looks familiar. Let's extract some of these data and plot them now.
Select data from a specific topic
We use the bagselect command to get only a limited set of data; first, let's grab the data from odometry, which is our current pose information as gathered from the simulator.
StartTime: 2.7139e+03
EndTime: 2.8485e+03
NumMessages: 125316
AvailableTopics: [1x3 table]
MessageList: [125316x4 table]
In order to plot these data, I will want to further extract the data points I will be using to plot as a timeseries. The trivial command for this is:
timeseries
Name: '/azcar_sim/odom Properties'
Time: [125316x1 double]
TimeInfo: [1x1 tsdata.timemetadata]
Data: [125316x2 double]
DataInfo: [1x1 tsdata.datametadata]
Plot data from this topic as a timeseries
Let's now plot away, as a function of time.
>> legend({'X position','Y position'})
You can see that there is a lot of data in the beginning of this plot that is pretty meaningless. Your plots may be such that you want to be able to "skip" to a point where things get interesting---perhaps where you send your first nonzero control input.
Find first nonzero control input time value
We begin by selecting a new topic from the bagfile
Like before, we would like a timeseries respresentation of these data:
Plotting these, we see the same trend of (mostly) uninteresting data:
plot(cmd_vel_safe.Time,cmd_vel_safe.Data(:,1),cmd_vel_safe.Time,cmd_vel_safe.Data(:,2))
legend({'Commanded velocity','Commanded steering'})
We can look for where data become interesting by finding the difference between commanded velocity and steering values, and looking for the first one that is nonzero.
>> find(veldiffs)
9672
This is a little hard to read: diff will find the element-wise difference between value in a vector, so it is telling us the difference in the velocity (as commanded) between each element. There are two points where the velocity is commanded to be a different value, at index 8937 (presumably where we speed up) and at 9672 (presumably where we hit the brakes so we don't collide with a jersey barrier).
We can check this easily enough by looking near this area in the original array.
Further, we can confirm that this corresponds to the time we are interested in in the plot by printing the value at that time:
Looking up at the figure from the plot, you can verify that the "step input" in velocity occurs just before 2800, so this computes pretty well.
Likewise, we can look at values in the commanded steering, but here we would expect a larger number of changes to the control inputs, because steering is the output of a feedback law. Let's confirm that:
>> indices=find(deltadiffs);
>> length(indices)
Of course, the interesting value will be the very first one of these points, so let's look near indicies(1) inside the cmd_vel_safe.Data, column 2.
0
0
0
0
0
0
0
0
0
0
1.8403
1.8403
1.8407
1.8407
1.8407
1.8421
1.8421
1.8438
1.8438
1.8438
Again, we see that interesting data start popping out at or near the first index.
Comparing these to the other bagselect that gave us odometry, let's see if the times correspond to one another by the same index:
So, we cannot naively compare the values across different bagselects. The reason for this is that the cmd_vel_safe topic may be published at a different rate, and must therefore be considered as a different stream. Nonetheless, we can account for this by finding the nearest index to the time that we consider to be interesting.
Creates temp array, indicating which indices are greater than the interesting time
Finds the first element in this array.
You may, if you choose, back up this time a little to ensure you get the pre-commanded state. Now, we're ready to plot. Note that the plot looks a little uglier now that we are plotting only a subset of the data, but it is fairly readable if you know how to read such commands.
plot(odom.Time(odomIndex(1):end),odom.Data(odomIndex(1):end,1),...
odom.Time(odomIndex(1):end),odom.Data(odomIndex(1):end,2),...
cmd_vel_safe.Time(vindices(1):end),cmd_vel_safe.Data(vindices(1):end,1),...
cmd_vel_safe.Time(vindices(1):end),cmd_vel_safe.Data(vindices(1):end,2));
legend({'X position','Y position','cmd velocity','cmd steering'})
Plot (x,y) coordinates only
If your only interest is to see where you went:
plot(odom.Data(:,1),odom.Data(:,2))
axis equal
legend('(x,y) position');
xlabel('X position')
ylabel('Y position')
And you are rewarded with the path trace. Compare this with what you see on rviz