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

Subscriber for rqt plugin

asked 2022-05-30 16:33:00 -0500

Mix_MicDev gravatar image

Hi, I created an rqt plugin by following the ROS tutorials. My goal is to constantly print on the UI data coming from a topic... I successfully subscribed to this topic once, but I don't know how I am supposed to be calling the subscriber constantly, in order to get the updated data. I tried adding a rospy.spin() in the __init__ method of my plugin but this causes a crash... Can somebody help me?

Here is my plugin code:

import os
import rospy
import rospkg
from std_msgs.msg import String
from rqt_mypkg.msg import custom

from qt_gui.plugin import Plugin
from .my_gui_interface import MyWidget
from PyQt5 import QtWidgets

class MyPlugin(Plugin):

    def __init__(self, context):
        super(MyPlugin, self).__init__(context)
        # Create QWidget
        self._widget = MyWidget(context)
        # Add widget to the user interface
        context.add_widget(self._widget)
        self.get_subscriber()

    def get_subscriber(self):
        rospy.Subscriber('test_topic', custom, self.callback)  # subscribe to the whatsapp topic and get the message
        print("Passed here")
        rospy.spin()

    def callback(self, data):  # This is the CallBack function called after subscribing the topic, to use the data
        rospy.loginfo("I heard Temp: {}".format(data.temperature_list))
        rospy.loginfo("I heard Pressure: {}".format(data.pressure_list))
        rospy.loginfo("I heard Altitude: {}".format(data.altitude_list))

    def shutdown_plugin(self):
        # TODO unregister all publishers here
        pass

    def save_settings(self, plugin_settings, instance_settings):
        # TODO save intrinsic configuration, usually using:
        # instance_settings.set_value(k, v)
        pass

    def restore_settings(self, plugin_settings, instance_settings):
        # TODO restore intrinsic configuration, usually using:
        # v = instance_settings.value(k)
        pass

    #def trigger_configuration(self):
        # Comment in to signal that the plugin has a way to configure
        # This will enable a setting button (gear icon) in each dock widget title bar
        # Usually used to open a modal configuration dialog

and here is my widget code:

import os
import rospy
import rospkg
from std_msgs.msg import String
from rqt_mypkg.msg import custom

from python_qt_binding import loadUi
from python_qt_binding.QtWidgets import QWidget
from PyQt5 import QtWidgets

class MyWidget(QWidget):
    def __init__(self, context):
        super(MyWidget, self).__init__()
        ui_file = os.path.join(rospkg.RosPack().get_path('rqt_mypkg'), 'resource', 'MyPlugin.ui')
        # Extend the widget with all attributes and children from UI file
        loadUi(ui_file, self)
        self.InitUI()
        self.temp = [2.2, 3.3, 4.4, 5.5, 6.6]
        self.pressure = [325, 35, 4.44, 588.5, 678.6]
        self.altitude = [500, 500, 600, 600, 800, 22, 22, 2, 211]
        self.data = custom()  # set the message you want to send to listener
        #rospy.Subscriber('test_topic', custom, self.callback)  # subscribe to the whatsapp topic and get the message

    def InitUI(self):
        self.Connection_Label.setText("Hello World")
        self.Exit_Button.setText("Click me")
        self.Exit_Button.clicked[bool].connect(self.Exit_Event)

    def Exit_Event(self):
        pub = rospy.Publisher('test_topic', custom, queue_size=10)  # create publisher on node whatsapp
        self.data.temperature_list = self.temp
        self.data.pressure_list = self.pressure
        self.data.altitude_list = self.altitude
        pub.publish(self.data)  # publish the message to the topic

    def callback(self, data):  # This is the CallBack function called after subscribing the topic, to use the data
        #rospy.loginfo("I heard Temp: {}".format ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-06-07 12:22:23 -0500

Hazel-rah gravatar image

You won't call the subscriber constantly, callback functions make that happen automatically. Whenever the topic gets a new message, the callback will run. (I didn't look in depth at your code, just answering the question)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-05-30 16:33:00 -0500

Seen: 192 times

Last updated: Jun 07 '23