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

Get HZ & BW from Rostopic Programatically

asked 2017-04-20 04:08:30 -0600

matansar gravatar image

Hi everyone,

I want to write a program in python and I need the value of HZ and BW (on specific topic). How can I do it (Using rostopic or something else)?

thanks in advance!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2017-04-20 21:06:55 -0600

Geoff gravatar image

You can use the same classes that the rostopic tool does to do this. If you import rostopic, you will find in that package several classes that gather statistics about topics. For example, the ROSTopicHz class is used to get the publishing rate. You can see how to use these classes by mimicking the functions that call them, such as _rostopic_hz. Basically, the statistics-gathering class instance is created, the topic of interest is subscribed to, and the callback on the instance of the statistics class is passed to the subscription. Then, after giving some time for messages to be processed, you can call a method of the stats class to get the current result.

Here's an example:

> import rospy, rostopic
> rospy.init_node('blurglesplort')
> r = rostopic.ROSTopicHz(-1)
> s = rospy.Subscriber('/joint_states', rospy.AnyMsg, r.callback_hz, callback_args='/joint_states')
> rospy.sleep(1)
> r.print_hz(['/joint_states'])
average rate: 46.186
        min: 0.000s max: 0.103s std dev: 0.03928s window: 643

Note that this is probably not a public API. If so, the API may change without notice.

edit flag offensive delete link more

Comments

thank you very much! but need a change: r.print_hz does not get param.

matansar gravatar image matansar  ( 2017-04-22 03:31:35 -0600 )edit
1

Yes, it looks like the print_hz function changed between Jade and Kinetic, and I was testing on Kinetic.

Geoff gravatar image Geoff  ( 2017-04-23 19:43:16 -0600 )edit

Could you help me, please? @Geoffhere is my question.

Redhwan gravatar image Redhwan  ( 2021-02-22 06:42:45 -0600 )edit

If you want to get the param, use the get_hz method instead of print_hzRef:

r.get_hz('/joint_states')[0]

get_hz method returns a tuple of stat results: rate, min_delta, max_delta, std_dev, n+1. The rate represents the hz i.e. [0].

Sj-Amani gravatar image Sj-Amani  ( 2021-11-04 03:15:02 -0600 )edit
0

answered 2021-02-06 12:44:08 -0600

Iranaphor gravatar image

Extending on Geoff's answer: bw is implemented slightly different to hz

Information on how these classes work can be found at rostopic.ROSTopicHz-class and rostopic.ROSTopicBandwidth-class

Extended Example:

import rospy, rostopic  
TOPIC = '/robot_pose'  
rospy.init_node('chosen_node_name')  

h = rostopic.ROSTopicHz(-1)  
s1 = rospy.Subscriber(TOPIC, rospy.AnyMsg, h.callback_hz, callback_args=TOPIC)  
rospy.sleep(1)  
h.print_hz([TOPIC])  

b = rostopic.ROSTopicBandwidth()  
s2 = rospy.Subscriber(TOPIC, rospy.AnyMsg, b.callback)  
rospy.sleep(1)  
b.print_bw()
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-04-20 04:08:30 -0600

Seen: 3,057 times

Last updated: Feb 06 '21