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

rospy ColorRGBA array messages changing all vectors

asked 2018-07-13 07:59:35 -0500

baakel gravatar image

So I'm trying to make certain LED's change color on certain events, I wrote a small program to test these changes

import rospy
from ledtracker.msg import ColorArray
from std_msgs.msg import ColorRGBA

def publisher():
    pub = rospy.Publisher('/ledscape_ros/array', ColorArray, queue_size=10)
    rospy.init_node('userstracker_vectors', anonymous=True)
    rate=rospy.Rate(0.2)
    msg = ColorRGBA()
    msg.r = 0.0
    msg.g = 0.0
    msg.b = 255.0
    msg.a = 255.0
    msga = ColorArray()
    for i in range(221):
        msga.leds.append(msg)

    while not rospy.is_shutdown():
        rospy.loginfo('Publishing')
        msga.leds[10].r = 255.0
        pub.publish(msga)
        rate.sleep()


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

If i try this, all LED's get colored red. I tried adding:

        msg2 = ColorRGBA()
        msg2.r = 255.0
        msga.leds.insert(10, msg2)
        print(msga.leds[10])
        print(msga.leds[11])

to see if that would help the problem but it didn't , this time it correctly colors only the 10th LED but then after the first iteration it continues to color the 11th and then the 12th and so forth till it has colored all LED's after the 10th. Is there something I'm missing on how to publish this array?

the message is simply

std_msgs/ColorRGBA[] leds

Thanks in advance!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-07-14 10:52:45 -0500

The problem is to do with how python doesn't copy objects unless you explicitly tell it to.

In your first piece of code you create a ColorRGBA object and add it 221 times to an array. However it doesn't make 221 copies, there are now 221 references to the same object. Hence why changing one appears to change them all.

Your modified code creates a new ColorRGBA object and inserts it into the array at position 10 increasing the length of the array by 1. This creates the result you want to the first iteration but because a new element is added each time the number of red LEDs grows by one each time too.

You want to create an array of 221 unique ColorRGBA objects then you will be able to update each element individually.

Hope this makes sense.

edit flag offensive delete link more

Comments

That's right. If you want to append 221 copies instead, import the copy module

import copy

And copy the message

 msga.leds.append(copy.copy(msg))
kev-the-dev gravatar image kev-the-dev  ( 2018-07-17 17:06:48 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-07-13 07:59:35 -0500

Seen: 663 times

Last updated: Jul 14 '18