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

how to access the msg in the subscriber callback in ros2 rclpy

asked 2021-06-27 18:04:35 -0500

ShehabAldeen gravatar image

Hello,

I am trying to run the following ros2 node. however, it seems that I cannot access the msg inside the callback function.

import rclpy
from rclpy.node import Node

import time
from std_msgs.msg import String


class MinimalSubscriber(Node):

    def __init__(self):
        super().__init__('minimal_subscriber')
        self.subscription = self.create_subscription(
            String,
            'topic',
            self.listener_callback,
            10)
        self.subscription  # prevent unused variable warning
        self.topub = 0

    def listener_callback(self, msg):
        self.topub = msg.data

    def printmsg (self):
        while True:
            self.get_logger().info('I heard: "%s"' % self.topub)
            time.sleep(0.5)

def main(args=None):
    rclpy.init(args=args)

    minimal_subscriber = MinimalSubscriber()
    minimal_subscriber.printmsg()

    rclpy.spin(minimal_subscriber)


if __name__ == '__main__':

    main()

if anyone has a clue, please help.

Thank you

edit retag flag offensive close merge delete

Comments

Have you tried ros2 topic echo to verify if publication is working as you expect?

abhishek47 gravatar image abhishek47  ( 2021-06-27 23:50:57 -0500 )edit
def printmsg (self):
    while True:
        self.get_logger().info('I heard: "%s"' % self.topub)
        time.sleep(0.5)

when would printmsg(..) return?

gvdhoorn gravatar image gvdhoorn  ( 2021-06-28 02:14:11 -0500 )edit

Yes, the topic is published

ShehabAldeen gravatar image ShehabAldeen  ( 2021-06-28 08:15:39 -0500 )edit

actually I want to have acess to the msg subscribed within a loop.

ShehabAldeen gravatar image ShehabAldeen  ( 2021-06-28 08:16:47 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2021-07-04 08:07:55 -0500

404RobotNotFound gravatar image

The problem you are running into is you are calling the minimal_subscriber.printmsg() function which sits in an infinite loop and you haven't started spinning the node to let the callbacks start receiving messages.

What you are trying to do is probably better done with a rclpy Timer. Here is a python example of one being used. Just pass your desired frequency to the timer constructor (which seems to be 2 for you, since you sleep for half a second), remove the while loop inside your printmsgfunction, and remove the call in the main function.

Spin should block so your program won't exit, and it should print the value of self.topub every half second.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-06-27 18:04:35 -0500

Seen: 1,146 times

Last updated: Jul 04 '21