How can i convert .mat file to a rosbag ?

asked 2020-11-01 14:10:49 -0500

aks gravatar image

updated 2020-11-18 07:57:25 -0500

Is it possible to convert a .mat file into rosbag ? One option would be to create a matlab publisher and subscribe to these messages via a ros node. Are there any alternatives ?

::: EDIT :::

I more or less found a solution but i get a rosbag of 31 MB in comparison to 1 MB of mat file. Here is how i approach the problem:

Firstly I installed the following msg in my ros environment. can_msgs

The can_msgs/Frame look like this :

Header header
uint32 id
bool is_rtr
bool is_extended
bool is_error
uint8 dlc
uint8[8] data

I load the *.mat file in python using scipy, extract the data out of it in idividual columns, each for Time, ID, Len and then i make 8 individual columns for my data[8] ◘as d0 to d7. I did this since each byte in CAN could have different signals mapped to it and i think it would be easier for the interpreter to decode the individual bytes. Although i am not sure if if should have 8 individual columns or i columns for 8 bytes.

Here is the final code :

from scipy.io import loadmat
import pandas as pd
import numpy as np
import rosbag
import rospy
from std_msgs.msg import Int32, String
from can_msgs.msg import Frame



file = 'Test_Sample.mat'

mat_file = loadmat(file)

mdata = mat_file['CAN_RAD']
mdtype = mdata.dtype

ndata = {n: mdata[n][0, 0] for n in mdtype.names}


data_time = ndata['Time']
data_ID = ndata['ID']
data_Len = ndata['Len']
data_raw = ndata['Data']




df = pd.DataFrame(data_time, columns = ['Time'])
df['ID'] = data_ID
df['Len'] = data_Len
df1 = pd.DataFrame(data_raw, columns = ['d0','d1','d2','d3','d4','d5','d6','d7'])


df2 = df.join(df1)

#so basically the dataframe has 11 columns now.
#Time ID Len d0 d1 d2 d3 d4 d5 d6 d7


can_msg = Frame()
#print(can_msg)

with rosbag.Bag('output.bag','w') as bag:
    for row in range(df2.shape[0]): 
        timestamp = rospy.Time.from_sec(df2['Time'][0])
        can_msg = Frame()
        can_msg.header.stamp = timestamp
        can_msg.id = df2['ID'][0]
        can_msg.dlc = df2['Len'][0]
        can_msg.data = list(np.uint8(((df2.iloc[0, 3:]))))
        bag.write("/can",can_msg,timestamp)

This gives me a rosbag as an output. I only have one question here now : The size of rosbag is 31MB in comparison to 1MB of matfile. Is it a normal behavior tha rosbags are relatively bigger in terms of space ?

ps: i have 347672 rows in my data.

edit retag flag offensive close merge delete

Comments

unless you have any other way to read and interpret the .mat file, e.g., in python, I can't imagine any other way.

chfritz gravatar image chfritz  ( 2020-11-01 15:41:00 -0500 )edit

Not an answer, but neufieldrobotics/rosbag_toolkit has something which goes in the opposite direction (ie: .bag to .mat). It may be useful as inspiration.

gvdhoorn gravatar image gvdhoorn  ( 2020-11-02 03:31:32 -0500 )edit