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

Subscriber - perform callback on 'most current' data received

asked 2019-05-15 01:45:25 -0500

Jan Tromp gravatar image

updated 2019-05-15 01:49:18 -0500

Hey everybody,

I've been messing a bit with a subscriber node and i'm getting stuck.

Little bit of background: I have a topic where a camera publishes images with a frequency of 10 hz (ish). I have another node subscribed to this topic. There the image is processed using open CV. The processing takes about 1 second. This means for every 10 images, 1 image is processed.

Now when i look at the images received by the subscriber i see that the images received are delayed, meaning that the next callback image 2 is processed, which was made about 0.9 second ago. The 3rd callback, image 3 is processed, leading to a delay of 1.8 s. etc... I think this has something to do with the queue size. I tried messing around with the basic chatter nodes from the tutorial to understand the problem a bit better and i made a simplified version of the problem:

publisher

#!/usr/bin/env python
# license removed for brevity
import rospy
from std_msgs.msg import String

def talker():
    pub = rospy.Publisher('chatter', String, queue_size=10)
    rospy.init_node('talker', anonymous=True)
    rate = rospy.Rate(1) # 10hz
    while not rospy.is_shutdown():
        hello_str = "hello world %s" % rospy.get_time()
        rospy.loginfo(hello_str)
        pub.publish(hello_str)
        rate.sleep()

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

subscriber:

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

def callback(data):
    rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    rospy.sleep(2)

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

    rospy.Subscriber("chatter", String, callback)
    print("done with callback")
    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

if __name__ == '__main__':
    listener()

Now, when i run both nodes, the publisher publisher at 1 message / s The subscriber receives the first message, waits 2 seconds, then receives the second message, etc. When i stop the publisher, the subscriber keeps receiving messages(probably since they are stored in a buffer)

Then set the queue size to 1, and ran the nodes again. This gave me the same result.

I want the subscriber to do something with the most up to date message, so deleting or not caring about all the messages received before. The reason for this is because i'm using this for a vision application, so i need the processing to process the latest image.

So, my question:

Is there a way to tell my subscriber (or publisher) to delete all stored messages or to start callback on the latest received image?

Kind regards, Jan Tromp.

edit retag flag offensive close merge delete

Comments

Is there a way to tell my subscriber (or publisher) to delete all stored messages or to start callback on the latest received image?

I'm sure you've already looked for solutions to your problem before posting here.

Could you add what you've tried and what didn't work?

It might also help if you could link to Q&As here on ROS Answers that you've found, so that we don't suggest the same things.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 01:59:59 -0500 )edit

I did look around for options to solve this problem, but apperantly i was searching in the wrong direction. I found a solution and explained it in my answer.

Jan Tromp gravatar image Jan Tromp  ( 2019-05-15 02:12:31 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
1

answered 2019-05-16 01:55:51 -0500

gvdhoorn gravatar image

updated 2019-05-16 02:03:08 -0500

I don't want the node to process images when the robot is moving. so this parameter is there so i can tell the node "now i want you to actually process an image"

It would appear that you have the following situation:

  1. camera (driver) that continuously publishes sensor_msgs/Image messages to a topic
  2. physical camera is mounted on the robot EEF
  3. image processing should happen only when requested

The question you posted seems to be an example of an xy-problem: you're asking about a detail of a solution you've picked, instead of about the actual problem. The answers you receive are then focused on the implementation detail, instead of the bigger picture.

I would propose to implement what you describe in the following way:

  1. write a service or action server and expose a ProcessImage service or action (I would suggest to use a more descriptive name, this is of course just an example)
  2. in the service/action callback, use rospy.wait_for_message(..) (docs) to retrieve a single Image from the camera stream
  3. process the image according to whatever parameters have been passed as part of the service request or the action goal
  4. return the result of the processing to the caller

Such a setup would seem to cover all your requirements: it only processes images when requested and it only works on the "latest data".

In addition it doesn't require any bookkeeping in your node, no disabling of callbacks, no queue_size tweaking, does not poll the parameter server at a high frequency and uses appropriate communication patterns for the interaction between service consumer and provider.

There does not seem to be a need to store Images at all in the service provider, nor is there a need to be notified of each and every message that gets published to the camera's topic. If the camera driver was not publishing continuously, this would be a different matter, but as it stands now I believe sampling a single message from the continuous stream whenever it is needed makes the most sense.

edit flag offensive delete link more

Comments

PS: I would recommend to use an action server here as they essentially allow you to invoke them as asynchronous services (ie: non-blocking to your caller). It's slightly more complicated to implement, but the advantages outweigh that easily.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-16 02:02:19 -0500 )edit
1

answered 2019-05-15 02:18:39 -0500

pavel92 gravatar image

updated 2019-05-15 02:21:33 -0500

Check the rospy subscriber API. The queue size might default to infinite so you can try adding queue_size=1:

rospy.Subscriber("chatter", String, callback, queue_size=1)
edit flag offensive delete link more

Comments

2

Actually, I believe to achieve the behaviour the OP asked for, the queue_size should be set to None instead. I'm basing this on #q269855, where it apparently worked for the OP. The docs state:

queue_size (int) - maximum number of messages to receive at a time. This will generally be 1 or None (infinite, default).

So None may not be the correct choice.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 02:39:11 -0500 )edit

The camera i'm working with is a pickit 3d camera. it is a "ROS integrated camera", meaning the camera has a ROS server running on its controller. The controller publishes the camera images (rgb and pointcloud, for this question i'm only interested in the rgb). Because the publisher node is in the controller, i am not able to change its code, hence i'm not able to change the queue size.

I think if this was possible this would fix the problem though.

Thanks for your reply!

Jan Tromp gravatar image Jan Tromp  ( 2019-05-15 06:13:45 -0500 )edit
1

The queue_size should be set on the subscriber. Not the publisher.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 06:16:33 -0500 )edit

Oh really? But how does that work in the python code then? If you look at my publisher and subscriber node the publisher is the one where queue_size is set, the subscriber doesn't have this at all.

pub = rospy.Publisher('chatter', String, queue_size=10)

Am i missing something?

Jan Tromp gravatar image Jan Tromp  ( 2019-05-15 06:20:30 -0500 )edit

Here's the documentation: rospy.topics.Subscriber. Note the queue_size argument.

But again: this may not actually work. #q269855 is unclear.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 06:21:58 -0500 )edit

Okay i see, didn't know this was possible. Though, this is a good solution for most of the people having this problem, in my case i do think i need the parameter (see my own answer). The reason for this is because i have the camera on a robot arm. The parameter "do callback_test" will decide whether the callback function is actually executed. This is necessary since I don't want the node to process images when the robot is moving. so this parameter is there so i can tell the node "now i want you to actually process an image"

In the link you provided one of the answers is using an action. I want to tell beforehand, the image is published on a topic so I (think I) have to use a subscriber.

Jan Tromp gravatar image Jan Tromp  ( 2019-05-15 06:40:31 -0500 )edit

The reason for this is because i have the camera on a robot arm. The parameter "do callback_test" will decide whether the callback function is actually executed. This is necessary since I don't want the node to process images when the robot is moving. so this parameter is there so i can tell the node "now i want you to actually process an image"

This starts to sound like an xy-problem.

In any case: it's perfectly possible to receive a single message from a topic. See #q270298 for C++ and #q292582 for the Python version of that.

so i can tell the node "now i want you to actually process an image"

if you want to be able to coordinate computation like that, I'd indeed recommend to use something other than topics, such as an action.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 06:45:32 -0500 )edit


The parameter "do callback_test" will decide whether the callback function is actually executed. This is necessary since I don't want the node to process images when the robot is moving. so this parameter is there so i can tell the node "now i want you to actually process an image"


In this case you can have a process_image() method that checks whether you need to process the image in the callback rather than messing with the callback execution. You can do smth like this:

def callback(data):
    if not process_image()
       return
    image processing logic...
pavel92 gravatar image pavel92  ( 2019-05-16 01:25:15 -0500 )edit
0

answered 2019-05-15 02:10:18 -0500

Jan Tromp gravatar image

updated 2019-05-15 06:14:43 -0500

Funny, I did look around a lot but i didn't really know what to look for. After typing this question, i was about to continue to another part of the project as i came across this link It suggested to 'dump' the stored images by letting the callback " temporarily do nothing". So i implemented this to my code and it did solve my problem. The updated subscriber and publisher are below.

subscriber:

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

def callback(data):
    if rospy.get_param("/do_callback_test") == True:
        rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
        rospy.sleep(2)
    else:
        pass

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

    rospy.Subscriber("chatter", String, callback)
    print("done with callback")
    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

if __name__ == '__main__':
    listener()

The output of the subscriber gave the following:

[INFO] [1557910478.891510]: /listener_18047_1557910462361I heard hello world 1557910472.84
[INFO] [1557910480.897341]: /listener_18047_1557910462361I heard hello world 1557910473.84
[INFO] [1557910482.902606]: /listener_18047_1557910462361I heard hello world 1557910474.84
[INFO] [1557910498.843681]: /listener_18047_1557910462361I heard hello world 1557910498.84
[INFO] [1557910500.852232]: /listener_18047_1557910462361I heard hello world 1557910499.84

After the 3rd print i set the parameter "/do_callback" to false, which made the subscriber just "pass" the callback. Then, when i made the parameter high again after 24 seconds, the subscriber printed out the information again, using the newest received data!

edit flag offensive delete link more

Comments

1

This is a work-around at best and I would not recommend you'd implement it this way. It is not needed.

Additionally: invoking rospy.get_param(..) in msg callbacks is not recommended, as it incurs quite a bit of overhead to retrieve the parameter value on each callback (essentially a full XMLRPC call).

gvdhoorn gravatar image gvdhoorn  ( 2019-05-15 02:39:36 -0500 )edit

This is a work-around at best and I would not recommend you'd implement it this way. It is not needed.

What do you mean with it's not needed?

quite a bit of overhead to retrieve the parameter value on each callback (essentially a full XMLRPC call).

What do you mean with this?

I'm sorry i'm not that familiar with the ROS vocabulary and english is not my main language :p

Jan Tromp gravatar image Jan Tromp  ( 2019-05-15 06:16:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-05-15 01:45:25 -0500

Seen: 2,781 times

Last updated: May 16 '19