Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rospy subscriber to Image topic high CPU in noetic vs. melodic #2374

Open
franzpeter124 opened this issue Aug 14, 2024 · 0 comments
Open

Rospy subscriber to Image topic high CPU in noetic vs. melodic #2374

franzpeter124 opened this issue Aug 14, 2024 · 0 comments

Comments

@franzpeter124
Copy link

During migration from melodic to noetic, I found that a subscription to a Image topic is very costly on noetic.
I found this on my laptop as well as on Nvidia Jetson.
Even though the callback does nothing and just pass, the subscriber node will take up much CPU.

I have compared melodic vs. noetic on the same laptop, both with plain ROS installation on a separate OS.

Image size Frequency CPU publisher CPU subscriber
melodic 2000 15 25% 12%
noetic 2000 15 15% 25%
melodic 3000 30 95% 45%
noetic 3000 30 60% 90%

In my application I have multiple nodes subscribing to one Image topic, so this issue sums up over multiple nodes and results in very high overall CPU usage.

Questions:

  • What is the reason for this? Looks like melodic and noetic have different underlying data transport
  • How can I get back to the low subscriber CPU usage from melodic?
  • Can a simple parameter change like queue_sizeor similar help?

Reproduce

Minimal example with publisher and subscriber of Image topic:
Publisher:

#!/usr/bin/env python

import rospy
from sensor_msgs.msg import Image
import numpy as np
from cv_bridge import CvBridge

def publisher():
    # Initialize the ROS node
    rospy.init_node('image_publisher_node', anonymous=True)

    # Create a publisher to the 'white_image' topic
    pub = rospy.Publisher('white_image', Image, queue_size=1)

    # Set the loop frequency
    rate = rospy.Rate(30)  # 15 Hz

    # Create an all-white image
    size = 3000
    white_image = np.ones((size, size, 3), np.uint8) * 255

    # Initialize the CvBridge class
    bridge = CvBridge()

    while not rospy.is_shutdown():
        # Convert the image to a ROS Image message
        ros_image = bridge.cv2_to_imgmsg(white_image, encoding="bgr8")

        # Publish the image
        pub.publish(ros_image)

        # Sleep to maintain the desired loop rate
        rate.sleep()


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

Subscriber:

#!/usr/bin/env python

import rospy
from sensor_msgs.msg import Image


def callback(data):
    pass

def subscriber():
    # Initialize the ROS node
    rospy.init_node('image_subscriber_node', anonymous=True)

    # Subscribe to the 'white_image' topic
    rospy.Subscriber('white_image', Image, callback, queue_size=1)

    # Spin to keep the script running
    rospy.spin()


if __name__ == '__main__':
    subscriber()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant