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

Revision history [back]

This is not the answer because it does not work, but I think it is probably close to the right answer. Hopefully someone can comment on what exactly is wrong with this code.

This is an attempt at an RQT plugin in C++ that passes ROS topic data to a GUI widget. I started with the RQT Example CPP files (https://github.com/lucasw/rqt_mypkg) that the ROS Tutorial points to (http://wiki.ros.org/rqt/Tutorials/Writing%20a%20C%2B%2B%20Plugin). Then I tried to add signal/slot code based on the QT Signal/Slot documentation (http://doc.qt.io/qt-4.8/signalsandslots.html).

It compiles and it runs. But it gives the following warning when it runs and the connection is obviously not made:

Object::connect: No such signal rqt_example_cpp::MyPlugin::setDataValue(int)
Object::connect: (sender name:   'MyPlugin')
Object::connect: (receiver name: 'data_myData')

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 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);
  virtual void shutdownPlugin();
  virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const;
  virtual void restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings);

  // Comment in to signal that the plugin has a way to configure it
  // bool hasConfiguration() const;
  // void triggerConfiguration();
private:
  Ui::MyPluginWidget ui_;
  QWidget* widget_;

  // kurt added all these
  ros::NodeHandle ros_node_handle;
  ros::Subscriber my_subscriber;
  void ros_data_callback(const std_msgs::Int32 message);

// kurt added this section
public slots:
  void setDataValue(int value);

// kurt added this section
signals:
  void setText(QString str);



};

}  // namespace rqt_example_cpp
#endif  // rqt_example_cpp_my_plugin_H

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)
{
  // Constructor is called first before initPlugin function, needless to say.

  // give QObjects reasonable names
  setObjectName("MyPlugin");
}

void MyPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{
  // access standalone command line arguments
  QStringList argv = context.argv();
  // create QWidget
  widget_ = new QWidget();
  // extend the widget with all attributes and children from UI file
  ui_.setupUi(widget_);
  // add widget to the user interface
  context.addWidget(widget_);

  // kurt added this subscriber
  my_subscriber = ros_node_handle.subscribe("my_data", 1, &MyPlugin::ros_data_callback, this);

   // kurt added this signal/slot connector
  QObject::connect( this, SIGNAL(setDataValue(int)),
            ui_.data_myData, SLOT(setText(const QString))   );

}

void MyPlugin::shutdownPlugin()
{
  // TODO unregister all publishers here
}

void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
{
  // TODO save intrinsic configuration, usually using:
  // instance_settings.setValue(k, v)
}

void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
{
  // TODO restore intrinsic configuration, usually using:
  // v = instance_settings.value(k)
}

// kurt added this ROS topic callback
void MyPlugin::ros_data_callback(const std_msgs::Int32 message) {
    printf("ROS callback saw data change.\n");
    MyPlugin::setDataValue(message.data);
}

// kurt added this slot routine
void MyPlugin::setDataValue(int value) {
    printf("QT slot routine saw data change.\n");
    QString str(QString::number(value));
    emit setText(str);
}

/*bool hasConfiguration() const
{
  return true;
}

void triggerConfiguration()
{
  // Usually used to open a dialog to offer the user a set of configuration
}*/

} // namespace
PLUGINLIB_DECLARE_CLASS(rqt_example_cpp, MyPlugin, rqt_example_cpp::MyPlugin, rqt_gui_cpp::Plugin)

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: rgb(0, 255, 0); background-color: rgb(0, 0, 0);</string>
   </property>
  </widget>

 </widget>

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

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) {
    QString str(QString::number(message.data));
    // this line actually calls the setText() routine on the GUI's QLabel 
    // via the connection of signal and slot
    emit setText(str);
    // another signal is used to set the color of the widget
    if (message.data > 9) {
        emit setStyleSheet("color: black; background-color: red;");
    }
    else {
        emit setStyleSheet("color: green; background-color: black;");
    }
}

} // namespace
PLUGINLIB_DECLARE_CLASS(rqt_example_cpp, MyPlugin, rqt_example_cpp::MyPlugin, rqt_gui_cpp::Plugin)

OLD, ORIGINAL ANSWER IS BELOW:

This is not the answer because it does not work, but I think it is probably close to the right answer. Hopefully someone can comment on what exactly is wrong with this code.

This is an attempt at an RQT plugin in C++ that passes ROS topic data to a GUI widget. I started with the RQT Example CPP files (https://github.com/lucasw/rqt_mypkg) that the ROS Tutorial points to (http://wiki.ros.org/rqt/Tutorials/Writing%20a%20C%2B%2B%20Plugin). Then I tried to add signal/slot code based on the QT Signal/Slot documentation (http://doc.qt.io/qt-4.8/signalsandslots.html).

It compiles and it runs. But it gives the following warning when it runs and the connection is obviously not made:

Object::connect: No such signal rqt_example_cpp::MyPlugin::setDataValue(int)
Object::connect: (sender name:   'MyPlugin')
Object::connect: (receiver name: 'data_myData')

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 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);
  virtual void shutdownPlugin();
  virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const;
  virtual void restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings);

  // Comment in to signal that the plugin has a way to configure it
  // bool hasConfiguration() const;
  // void triggerConfiguration();
private:
  Ui::MyPluginWidget ui_;
  QWidget* widget_;

  // kurt added all these
  ros::NodeHandle ros_node_handle;
  ros::Subscriber my_subscriber;
  void ros_data_callback(const std_msgs::Int32 message);

// kurt added this section
public slots:
  void setDataValue(int value);

// kurt added this section
signals:
  void setText(QString str);



};

}  // namespace rqt_example_cpp
#endif  // rqt_example_cpp_my_plugin_H

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)
{
  // Constructor is called first before initPlugin function, needless to say.

  // give QObjects reasonable names
  setObjectName("MyPlugin");
}

void MyPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{
  // access standalone command line arguments
  QStringList argv = context.argv();
  // create QWidget
  widget_ = new QWidget();
  // extend the widget with all attributes and children from UI file
  ui_.setupUi(widget_);
  // add widget to the user interface
  context.addWidget(widget_);

  // kurt added this subscriber
  my_subscriber = ros_node_handle.subscribe("my_data", 1, &MyPlugin::ros_data_callback, this);

   // kurt added this signal/slot connector
  QObject::connect( this, SIGNAL(setDataValue(int)),
            ui_.data_myData, SLOT(setText(const QString))   );

}

void MyPlugin::shutdownPlugin()
{
  // TODO unregister all publishers here
}

void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
{
  // TODO save intrinsic configuration, usually using:
  // instance_settings.setValue(k, v)
}

void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
{
  // TODO restore intrinsic configuration, usually using:
  // v = instance_settings.value(k)
}

// kurt added this ROS topic callback
void MyPlugin::ros_data_callback(const std_msgs::Int32 message) {
    printf("ROS callback saw data change.\n");
    MyPlugin::setDataValue(message.data);
}

// kurt added this slot routine
void MyPlugin::setDataValue(int value) {
    printf("QT slot routine saw data change.\n");
    QString str(QString::number(value));
    emit setText(str);
}

/*bool hasConfiguration() const
{
  return true;
}

void triggerConfiguration()
{
  // Usually used to open a dialog to offer the user a set of configuration
}*/

} // namespace
PLUGINLIB_DECLARE_CLASS(rqt_example_cpp, MyPlugin, rqt_example_cpp::MyPlugin, rqt_gui_cpp::Plugin)

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: rgb(0, 255, 0); background-color: rgb(0, 0, 0);</string>
   </property>
  </widget>

 </widget>

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