Error exchanging list of floats in a topic

匆匆过客 提交于 2019-12-24 07:18:52

问题


I think that the issue is silly.

I'd like to run the code on two computers and I need to use a list. I followed this Tutorials

I used my PC as a talker and computer of the robot as a listener.

when running the code on my PC, the output is good as I needed.

[INFO] [1574230834.705510]: [3.0, 2.1]
[INFO] [1574230834.805443]: [3.0, 2.1]

but once running the code on the computer of the robot, the output is:

Traceback (most recent call last):
  File "/home/redhwan/learn.py", line 28, in <module>
    talker()
  File "/home/redhwan/learn.py", line 23, in talker
    pub.publish(position.data)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/topics.py", line 886, in publish
    raise ROSSerializationException(str(e))
rospy.exceptions.ROSSerializationException: <class 'struct.error'>: 'required argument is not a float' when writing 'data: [3.0, 2.1]'

full code on PC:

#!/usr/bin/env python
import rospy
from std_msgs.msg import Float32
x = 3.0
y = 2.1

def talker():
    # if a == None:
    pub = rospy.Publisher('position', Float32, queue_size=10)
    rospy.init_node('talker', anonymous=True)
    # rospy.init_node('talker')
    rate = rospy.Rate(10) # 10hz

    while not rospy.is_shutdown():
        position = Float32()
        a = [x,y]
        # a = x
        position.data = list(a)
        # position.data = a
        # hello_str = [5.0 , 6.1]
        rospy.loginfo(position.data)

        pub.publish(position.data)
        rate.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass

full code on the computer of the robot:

#!/usr/bin/env python
import rospy
from std_msgs.msg import Float32


def callback(data):
    # a = list(data)
    a = data.data
    print a

def listener():

    rospy.init_node('listener', anonymous=True)

    rospy.Subscriber("position", Float32, callback)

    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()


if __name__ == '__main__':
    listener()

when using one number as float everything is OK.

I understand how to publish and subscribe to them separately as the float but I'd like to do it as list

Any ideas or suggestion, it would be appreciated.


回答1:


When you exchange messages in ROS is preferred to adopt standard messages if there is something relatively simple. Of course, when you develop more sophisticated systems (or modules), you can implement your own custom messages.

So in the case of float array, Float32MultiArray is your friend. Populating the message in one side will look like that (just an example using a 2 elements float32 array) in C++:

.
.
.
while (ros::ok())
  {
    std_msgs::Float32MultiArray velocities;
    velocities.layout.dim.push_back(std_msgs::MultiArrayDimension());
    velocities.layout.dim[0].label = "velocities";
    velocities.layout.dim[0].size = 2;
    velocities.layout.dim[0].stride = 1;

    velocities.data.clear();

    velocities.data.push_back(count % 255);
    velocities.data.push_back(-(count % 255));

    velocities_demo_pub.publish(velocities);

    ros::spinOnce();

    loop_rate.sleep();
    ++count;
  }
.
.
.

in Python for 8 elements array an example will look like:

. . . while not rospy.is_shutdown():

# compose the multiarray message
pwmVelocities = Float32MultiArray()

myLayout = MultiArrayLayout()

myMultiArrayDimension = MultiArrayDimension()

myMultiArrayDimension.label = "motion_cmd"
myMultiArrayDimension.size = 1
myMultiArrayDimension.stride = 8

myLayout.dim = [myMultiArrayDimension]
myLayout.data_offset = 0

pwmVelocities.layout = myLayout
pwmVelocities.data = [0, 10.0, 0, 10.0, 0, 10.0, 0, 10.0]

# publish the message and log in terminal
pub.publish(pwmVelocities)
rospy.loginfo("I'm publishing: [%f, %f, %f, %f, %f, %f, %f, %f]" % (pwmVelocities.data[0], pwmVelocities.data[1],
  pwmVelocities.data[2], pwmVelocities.data[3], pwmVelocities.data[4], pwmVelocities.data[5],
  pwmVelocities.data[6], pwmVelocities.data[7]))

# repeat
r.sleep()

. . .

and on the other side your callback (in C++), will look like:

.
.
.
void hardware_interface::velocity_callback(const std_msgs::Float32MultiArray::ConstPtr &msg) {
    //velocities.clear();
    if (velocities.size() == 0) {
        velocities.push_back(msg->data[0]);
        velocities.push_back(msg->data[1]);
    } else {
        velocities[0] = msg->data[0];
        velocities[1] = msg->data[1];
    }
    vel1 = msg->data[0];
    vel2 = msg->data[1];
    //ROS_INFO("Vel_left: [%f] - Vel_right: [%f]", vel1 , vel2);
}
.
.
.

Hope that you got an idea...if you need something more drop me a line!



来源:https://stackoverflow.com/questions/58950233/error-exchanging-list-of-floats-in-a-topic

易学教程内所有资源均来自网络或用户发布的内容,如有违反法律规定的内容欢迎反馈
该文章没有解决你所遇到的问题?点击提问,说说你的问题,让更多的人一起探讨吧!