Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

[rospy] Improve rospy.logXXX_throttle performance#1091

Merged
dirk-thomas merged 1 commit intoros:lunar-develfrom
otamachan:lunar-devel-imporve-rospy-log-throttle
Jul 10, 2017
Merged

[rospy] Improve rospy.logXXX_throttle performance#1091
dirk-thomas merged 1 commit intoros:lunar-develfrom
otamachan:lunar-devel-imporve-rospy-log-throttle

Conversation

@otamachan
Copy link
Copy Markdown
Contributor

Hello,

I found that the performance of rospy.logXXX_throttle gets even worse than normal rospy.logXXX when the stack is rather deep such as in a subscriber callback.
I've tested the following example

#!/usr/bin/env python
from __future__ import print_function

import time
import rospy
import std_msgs.msg

total = 0.0
count = 0
def callback(data):
    global total, count
    start = time.time()
    # rospy.loginfo("test")               # normal rospy.logXXXX
    rospy.loginfo_throttle(1.0, "test")   # rospy.logXXXX_throttle
    total += time.time() - start
    count += 1

rospy.init_node("test", anonymous=True)
pub = rospy.Publisher("test", std_msgs.msg.String, queue_size=10)
sub = rospy.Subscriber("test", std_msgs.msg.String, callback)

while not rospy.is_shutdown():
    pub.publish("hello")
    rospy.sleep(0.01)

print("average={0}ms".format(total/count*1000.0))

and got the following result.

  • rospy.logXXX: 0.60ms per call
[INFO] [WallTime: 1499434598.555137] test
[INFO] [WallTime: 1499434598.565363] test
[INFO] [WallTime: 1499434598.575602] test
[INFO] [WallTime: 1499434598.585872] test
^Caverage=0.599916740383ms
  • rospy.logXXX_throttle: 0.99ms per call (even it is throttled)
[INFO] [WallTime: 1499434540.990035] test
[INFO] [WallTime: 1499434541.995128] test
[INFO] [WallTime: 1499434543.000947] test
^Caverage=0.985359591107ms

According to the stakcoverflow, inspect.stack is an expensive function because it gathers all the frames and their contexts.
This PR changes the way to get the parent frame and improve its performance.

The final result is

  • rospy.logXXX_throttle: 0.15ms per call
[INFO] [WallTime: 1499435067.096333] test
[INFO] [WallTime: 1499435068.101505] test
[INFO] [WallTime: 1499435069.107257] test
^Caverage=0.148712320531ms

@otamachan otamachan force-pushed the lunar-devel-imporve-rospy-log-throttle branch from b79c80d to f6a4df1 Compare July 7, 2017 14:46
@dirk-thomas
Copy link
Copy Markdown
Member

Thank you for the improvement.

@wkentaro Since you implemented this feature could you give this patch a try since the tests don't cover the actual frame information.

@wkentaro
Copy link
Copy Markdown
Contributor

wkentaro commented Jul 9, 2017

LGTM. It works and improves the performance.

@dirk-thomas
Copy link
Copy Markdown
Member

Thanks for testing.

@otamachan
Copy link
Copy Markdown
Contributor Author

@wkentaro Thanks for taking your time and testing.

Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants