ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

In publish raise ROSSerializationException(str(e))

asked 2019-04-11 03:37:45 -0500

elcinerdogan gravatar image

updated 2019-04-11 06:15:44 -0500

In my package that I created, there are 3 nodes currently. I also generate a custom message which is "AnchorScan".

First node does some stuff and only publishes from /IPS topic. Second node subscribes to the /IPS topic, takes the information, do some stuff and publishes another information from /selectedAnchors topic.

Until now everything works fine. But;

Third node subscribes to the /selectedAnchors topic and does some calculations however does not publish anything from /position topic.

After I run this command on terminal

rostopic echo /position

I received that kind of exception.

I tried to change the queue size, rate etc. but nothing worked fine.

All raised error is here:

Traceback (most recent call last):

File /home/user/my_ws/src/my_pkg/src/pkg_name/3rd_node.py", line 366, in <module>
    position_pub_sub()
  File "/home/user/my_ws/src/my_pkg/src/pkg_name/3rd_node.py", line 324, in position_pub_sub
    pub.publish(msg)     
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/topics.py", line 886, in publish
    raise ROSSerializationException(str(e))
rospy.exceptions.ROSSerializationException: field x must be a list or tuple type

Thank you in advance for any help!!!

https://github.com/ros/ros_comm/issue...


Edit:

Here is my code:

#!/usr/bin/env python
# license removed for brevity
import rospy
from math import sqrt

from random import randint
from random import uniform
from collections import OrderedDict

from std_msgs.msg import String
from my_pkg.msg import AnchorScan    

class CalcPos2D3AIte:   

    def __init__(self, SX, SY, SZ, AX, AY, AZ, BX, BY, BZ, TZ, das, dbs):

              ## DO STUFF
              ## DO STUFF
              ## DO STUFF 

        pre_TY = (N2 -(M21*N1/M11))/(M22-(M21*M12/M11))         
            pre_TX = ((-1*M21*N1/M11) + (M21*M12/M11)*pre_TY)/(-1*M21) 

                TX = pre_TX         
                TY = pre_TY 

        self.TX_cm = int(TX*100)        
            self.TY_cm = int(TY*100)        
            self.TZ_cm = int(TZ*100)

def position_pub_sub():

    rospy.init_node('test2_positioning_node', anonymous=True)
    rospy.Subscriber('selectedAnchors', AnchorScan, callback)
    pub = rospy.Publisher('position', AnchorScan, queue_size=2)    

    rate = rospy.Rate(10)    

    while not rospy.is_shutdown():

     if var_control:

        msg = AnchorScan()
        tagpos = CalcPos2D3AIte(SX, SY, SZ, AX, AY, AZ, BX, BY, BZ, TZ,das, dbs)

         msg.x = tagpos.TX_cm
         msg.y = tagpos.TY_cm
         msg.z = tagpos.TZ_cm

         pub.publish(msg)     

        pub_info = "\nTX = %f \nTY = %f \nTZ = %f \n\n" % (tagpos.TX_cm,tagpos.TY_cm,tagpos.TZ_cm)
        rospy.loginfo(pub_info)

    rate.sleep()

Here is my AnchorScan.msg what it looks like:

# Timestamp
#Header header 

int32[] AnchorID 

float64[] x
float64[] y
float64[] z

float64 distance

# according to "S"
float64[] DDOA_of_anchors
edit retag flag offensive close merge delete

Comments

The error you show is most likely caused by a mistake in the code of your "third node". Without you showing us the code, we cannot help you.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-11 04:48:48 -0500 )edit

You don't show any import statements. Are N2 and friends numpy vectors/matrices/arrays?


Edit: the error message shows:

pkg_name/3rd_node.py", line 324, in position_pub_sub

which line in the code you show is line 324? Where is position_pub_sub?

And: please include the definition of the AnchorScan message. I would also recommend to add something like print ("type of tagpos.TX_cm: {}".format(type(tagpos.TX_cm)) right before the line where the script fails. That would let you check what the type if of tagpos.TX_cm.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-11 05:56:36 -0500 )edit

I added the my code snippet. There is position_pub_sub function here and I publish and subscribe in this function. Also line 324 indicates the;

 pub.publish(msg)

in position_pub_sub function.

elcinerdogan gravatar image elcinerdogan  ( 2019-04-11 06:05:15 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-04-11 06:17:10 -0500

gvdhoorn gravatar image

updated 2019-04-11 06:18:07 -0500

Ok.

Your code snippet does this:

self.TX_cm = int(TX*100)
[..]
msg.x = tagpos.TX_cm

The message definition of AnchorScan shows this:

float64[] x

x is an array (or an unbounded list). You cannot assign a single int to a list.

You'll have to either use msg.x.append(..) or something like msg.x = [tagpos.TX_cm].

Please note btw: ROS uses (derived) SI units for everything, so positions use metres. It might be good not to use centimetres for anything.


Edit: btw: is this a different indoor_localization/AnchorScan than the one documented here? Because the one documented on the ROS wiki does not have float64[] x.

edit flag offensive delete link more

Comments

1

And some further comments: please don't use capitals in msg field names. That goes against the ROS best practices for naming things. See wiki/Names.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-11 06:25:34 -0500 )edit

How could I fail to notice... I changed the type of the tagpos.Tx_cm from int into float. And it works. Thankss soo much.

Btw: Here is different than my currently used msg.

elcinerdogan gravatar image elcinerdogan  ( 2019-04-11 06:31:57 -0500 )edit

I also consider your suggestion about ROS naming. Thanks again.

elcinerdogan gravatar image elcinerdogan  ( 2019-04-11 06:33:35 -0500 )edit

I changed the type of the tagpos.Tx_cm from int into float. And it works.

I'm not sure how that would help, seeing as AnchorScan.x is still a list in your message definition, and a single float is still not a list, but if it works for you. Ok.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-11 06:57:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-04-11 03:37:45 -0500

Seen: 7,515 times

Last updated: Apr 11 '19