ROS - SerializationError when writing a bagfile with custom ROS message

asked 2020-10-16 19:19:26 -0500

mostafa.husseinsh gravatar image

updated 2020-10-20 07:28:16 -0500

I have a created a custom ros message which has the following format

# Header information
std_msgs/Header header

# Model
string model

# Data
uint8[] data

The data is a list of 4D lists reading from csv file

def createData(csv_file): 
     x,y,z,w = np.loadtxt(dataFile, usecols=(0,1,2,3), \ skiprows=0, delimiter="\t", unpack=True) 
     p = [] 
     for p1, p2, p3, p4 in zip(x,y,z,w): 
        pt = [p1, p2, p3, p4] 
        p.append(pt)
     header = Header()
     header.stamp = rospy.rostime.Time.from_sec(time.time())
     header.frame_id = "main_frame"
     model = "sensor"
     msg = customMessage(header, model, p)
     return msg, p

with rosbag.Bag('test.bag', 'w') as bag:
    msg, points = createData(csv_file)
    bag.write(topic_name, msg)
bag.close()

where inside the customMessage(genpy.Message) class, I set the msg.data to p, msg.header to header, and msg.model to model I created a random data with this message type, and I am trying to write a bag file out of this

bag.write(topic_name, msg)

However I receive this error

Traceback (most recent call last):
  File "data2bag.py", line 306, in <module>
    bag.write(topic_name, msg)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosbag/bag.py", line 391, in write
    msg.serialize(self._buffer)
  File "data2bag.py", line 123, in serialize
    except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(locals().get('_x', self)))))
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 334, in _check_types
    check_type(n, t, getattr(self, n))
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 256, in check_type
    check_type(field_name+"[]", base_type, v)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 212, in check_type
    raise SerializationError('field %s must be unsigned integer type'%field_name)
genpy.message.SerializationError: field data[] must be unsigned integer type

The msg.data has a type of <type 'list'> which is the assumed type The writing of the bag file is successful if only the msg.data has a str type

Nevertheless, this does not make sense since it won't be working with a str data type

If I change the data to uint8 by: points = np.uint8(p)

I get this error instead

Traceback (most recent call last):
  File "data2bag.py", line 307, in <module>
    bag.write(topic_name, msg)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosbag/bag.py", line 391, in write
    msg.serialize(self._buffer)
  File "data2bag.py", line 123, in serialize
    except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(locals().get('_x', self)))))
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 334, in _check_types
    check_type(n, t, getattr(self, n))
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 254, in check_type
    raise SerializationError('field %s must be a list or tuple type'%field_name)
genpy.message.SerializationError: field data must be a list or ...
(more)
edit retag flag offensive close merge delete