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

example RQT plugin in C++ that uses signals/slots

asked 2016-02-12 14:36:36 -0500

updated 2016-02-16 10:59:00 -0500

I cannot for the life of me figure out how to use signals and slots to pass information to the GUI widget in an RQT plugin that is written in C++. The ROS Tutorial for creating a C++ RQT plugin doesn't even have any data widgets in the GUI, let alone any code to show how to use signals/slots to pipe data to a data widget: http://wiki.ros.org/rqt/Tutorials/Wri...

After several hours of trial and error, I was able to figure out a solution for using signals/slots in a Python RQT plugin, but I can't seem to make the stretch to C++.

Here is the python example I created starting from the ROS Tutorial for creating a python RQT plugin ( https://github.com/lucasw/rqt_mypkg ) and then adding some of this code from ROS Answers where a user asked how to use signals/slots in python: http://answers.ros.org/question/22415...

my_module.py:

import os
import rospy

from qt_gui.plugin import Plugin
from python_qt_binding import loadUi
from python_qt_binding.QtGui import QWidget
from std_msgs.msg import Int32
from PyQt4.QtCore import SIGNAL

class MyPlugin(Plugin):

    def __init__(self, context):
        super(MyPlugin, self).__init__(context)
        # Give QObjects reasonable names
        self.setObjectName('MyPlugin')

        # Process standalone plugin command-line arguments
        from argparse import ArgumentParser
        parser = ArgumentParser()
        # Add argument(s) to the parser.
        parser.add_argument("-q", "--quiet", action="store_true",
                      dest="quiet",
                      help="Put plugin in silent mode")
        args, unknowns = parser.parse_known_args(context.argv())
        if not args.quiet:
            print 'arguments: ', args
            print 'unknowns: ', unknowns

        # Create QWidget
        self._widget = QWidget()
        # Get path to UI file which is a sibling of this file
        # in this example the .ui and .py file are in the same folder
        ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'MyPlugin.ui')
        # Extend the widget with all attributes and children from UI file
        loadUi(ui_file, self._widget)
        # Give QObjects reasonable names
        self._widget.setObjectName('MyPluginUi')
        # Show _widget.windowTitle on left-top of each plugin (when 
        # it's set in _widget). This is useful when you open multiple 
        # plugins at once. Also if you open multiple instances of your 
        # plugin at once, these lines add number to make it easy to 
        # tell from pane to pane.
        if context.serial_number() > 1:
            self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
        # Add widget to the user interface
        context.add_widget(self._widget)

        # kurt added these lines
        self.sub = rospy.Subscriber('my_data', Int32, self.ros_msg_callback, queue_size=1)
        self.connect(self, SIGNAL("changeUI(PyQt_PyObject)"), self.monitoring_slot)

    # kurt added this callback
    def ros_msg_callback(self, data):
        self.emit(SIGNAL("changeUI(PyQt_PyObject)"), data)
        pass

    # kurt added this slot routine
    def monitoring_slot(self, data):
        self._widget.data_myData.setText(str(data))
        self._widget.data_myData.setStyleSheet("color: black; background-color: red;")
        pass

    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 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2016-02-12 16:05:07 -0500

updated 2016-02-16 09:40:46 -0500

I finally figured it out. Thanks for all the helpful comments below.

I was trying to define both the signal and slot in my own class, per the various QT examples I had found, but I really wanted to signal the existing slot in the existing QLabel class. For this scenario the solution is way simpler than the QT examples I was using which do not signal an existing slot in an existing class. This is confusing to new ROS users who need to signal existing QT widgets in their RQT plugins. This is exactly why I was (and still am) pushing for this signal/slot example code to be added to the ROS C++ RQT Plugin tutorial.

Here is a simple diagram for newbies: image description

Here is the GUI definition file my_plugin.ui:

<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
 <class>MyPluginWidget</class>

 <widget class="QWidget" name="MyPluginWidget">
  <property name="geometry">
   <rect>
    <x>0</x>
    <y>0</y>
    <width>400</width>
    <height>300</height>
   </rect>
  </property>
  <property name="windowTitle">
   <string>Form</string>
  </property>

  <!-- kurt added this widget -->
  <widget class="QLabel" name="label_myLabel">
   <property name="text">
    <string>Label:</string>
   </property>
   <property name="geometry">
    <rect>
     <x>10</x>
     <y>10</y>
     <width>50</width>
     <height>30</height>
    </rect>
   </property>
  </widget>

  <!-- kurt added this widget -->
  <widget class="QLabel" name="data_myData">
   <property name="text">
    <string>TBD</string>
   </property>
   <property name="geometry">
    <rect>
     <x>70</x>
     <y>10</y>
     <width>50</width>
     <height>30</height>
    </rect>
   </property>
   <property name="styleSheet">
    <string notr="true">color: green; background-color: black;</string>
   </property>
  </widget>

 </widget>

 <resources/>
 <connections/>
</ui>

Here is the header file my_plugin.h:

#ifndef rqt_example_cpp_my_plugin_H
#define rqt_example_cpp_my_plugin_H

#include <rqt_gui_cpp/plugin.h>
#include <rqt_example_cpp/ui_my_plugin.h>
#include <QWidget>

// kurt added these 3 includes
#include <ros/ros.h>
#include <std_msgs/Int32.h>
#include <QString>

namespace rqt_example_cpp {

class MyPlugin
  : public rqt_gui_cpp::Plugin
{
  Q_OBJECT
public:
  MyPlugin();
  virtual void initPlugin(qt_gui_cpp::PluginContext& context);

private:
  Ui::MyPluginWidget ui_;
  QWidget* widget_;

  // kurt added these lines to get data from a ROS Topic
  ros::NodeHandle ros_node_handle;
  ros::Subscriber my_subscriber;
  void ros_data_callback(const std_msgs::Int32 message);

// kurt added these signal definitions to pass data to QLabel on GUI
Q_SIGNALS:
  void setText(const QString str);
  void setStyleSheet(const QString str);

};

}  // namespace rqt_example_cpp
#endif  // rqt_example_cpp_my_plugin_H

And here is the source file my_plugin.cpp:

#include "rqt_example_cpp/my_plugin.h"
#include <pluginlib/class_list_macros.h>
#include <QStringList>

namespace rqt_example_cpp {

MyPlugin::MyPlugin()
  : rqt_gui_cpp::Plugin()
  , widget_(0)
{
  setObjectName("MyPlugin");
}

void MyPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{
  QStringList argv = context.argv();
  widget_ = new QWidget();
  ui_.setupUi(widget_);
  context.addWidget(widget_);

  // kurt added this ROS Topic subscriber
  my_subscriber = ros_node_handle.subscribe("my_data", 1, &MyPlugin::ros_data_callback, this);
   // kurt added these lines to connect the emitted signals below to the GUI's QLabel's public slots
  QObject::connect( this, SIGNAL(setText(const QString)),
            ui_.data_myData, SLOT(setText(const QString))   );
  QObject::connect( this, SIGNAL(setStyleSheet(const QString)),
            ui_.data_myData, SLOT(setStyleSheet(const QString)) );
}

// kurt added this ROS topic callback to get data from ROS and send signals to QLabel on GUI
void MyPlugin::ros_data_callback(const std_msgs::Int32 message ...
(more)
edit flag offensive delete link more

Comments

1

This is more a question related to Qt than ROS, I think. However, in the connect you are swapping signal and slot. If you declare setText as slot you have to put SLOT(setText()) in the connect. In the .h use Q_SIGNALS instead of signals and public Q_SLOTS instead of public slots.

rastaxe gravatar image rastaxe  ( 2016-02-13 04:16:40 -0500 )edit
1

You cannot connect signals and slots with different signatures.

kramer gravatar image kramer  ( 2016-02-13 09:45:13 -0500 )edit

"you cannot connect signals and slots with different signatures" Thanks. This is exactly why a simple working example would be helpful to have on the ROS RQT plugin tutorial site for new users to have as a starting point for their own RQT plugins.

Kurt Leucht gravatar image Kurt Leucht  ( 2016-02-14 12:00:34 -0500 )edit
1

Maybe you want to start with the Qt tutorials then since what you describe has nothing to do with rqt but how Qt signals and slots work. And I am sure there are really good tutorials out there for that topic.

Dirk Thomas gravatar image Dirk Thomas  ( 2016-02-14 13:52:08 -0500 )edit

"Maybe you want to start with the Qt tutorials". I did. As I said in my wrong answer above, I used the following documentation ( http://doc.qt.io/qt-4.8/signalsandslo... ) to try to integrate signals/slots into the simple example C++ RQT plugin. But it did not work. Maybe I'm just dumb.

Kurt Leucht gravatar image Kurt Leucht  ( 2016-02-14 16:38:05 -0500 )edit
1

As the other comments already point out you are swapping signals and slots (you declared setDataValue to be a slot but use it with SIGNAL(setDataValue(int)) and (b) try to connect two different signature (int with String).

Dirk Thomas gravatar image Dirk Thomas  ( 2016-02-15 11:57:56 -0500 )edit

Try something exactly as it is described in the Qt tutorial you referenced yourself: public slots: void setValue(int value); and signals: void valueChanged(int newValue);. And once that works try iterating from there toward what you would like to have.

Dirk Thomas gravatar image Dirk Thomas  ( 2016-02-15 11:59:53 -0500 )edit

Thanks for all the helpful comments! Turns out I was defining both the signal and slot in my code when I really only wanted to signal the existing slot in the QLabel class. The solution in this case was way simpler than all those QT signal/slot tutorials I was looking at.

Kurt Leucht gravatar image Kurt Leucht  ( 2016-02-16 09:42:38 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-02-12 14:36:36 -0500

Seen: 3,043 times

Last updated: Feb 16 '16