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

How to connect a signal to a publisher

asked 2016-07-06 19:05:15 -0500

Piero-31 gravatar image

updated 2016-07-11 16:46:03 -0500

Hi,

I am using a rqt plugin made with the tutorial and I have made a simple GUI composed with a slider and a button. I would like to connect the button, to send the value of the slider to a message. This message which contents a integer, would be publish when the button is clicked. Then in another file I have made a "listener" based on the tutorial and I would like to see on my screen the integer.

I can't catkin_make it because I have many errors. I know that I am mixing GUI and ros things, and signals and messages, I am lost. Can someone helpme with that ?

This is my header file :

#ifndef rqt_mypkg__my_plugin_H
#define rqt_mypkg__my_plugin_H

#include <rqt_gui_cpp/plugin.h>
#include <rqt_mypkg/ui_my_plugin.h>
#include <QWidget>
#include <QString>
#include <QList>

#include <ros/ros.h>

#include "std_msgs/String.h"
#include <std_msgs/Int8.h>


namespace rqt_mypkg {

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_;

  ros::NodeHandle ros_node_handle;
  ros::Publisher my_publisher;
  ros::Subscriber sub;


public Q_SLOTS:

  virtual void publier();



};
} // namespace
#endif // rqt_mypkg_my_plugin_H

This is my cpp file :

(I know that the thing I've done with the "dac=0 and dac=1" is not working and stupid but I wanted to test it.)

#include "rqt_mypkg/my_plugin.h"
#include <pluginlib/class_list_macros.h>
#include "ros/ros.h"
#include <QStringList>
#include "std_msgs/String.h"
#include <sstream>
#include <std_msgs/Int8.h>

int dac= 0;

namespace rqt_mypkg {

MyPlugin::MyPlugin()
  : rqt_gui_cpp::Plugin()
  , widget_(0)
{

  setObjectName("MyPlugin");
}

void MyPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{

  QStringList argv = context.argv();
  // create QWidget
  widget_ = new QWidget();



  ui_.setupUi(widget_);
  // add widget to the user interface
  context.addWidget(widget_);

connect(ui_.m_bouton, SIGNAL(clicked()), this, SLOT(publier()));
}

void MyPlugin::publier ()
{
  dac = 1;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv,"envoyeur");
  ros::NodeHandle ros_node_handle;



 ros::Publisher my_publisher = ros_node_hand

le.advertise<std_msgs::Int8>("chatter", 1000);
ros::Rate loop_rate(1);

 int count = 0;
while(ros::ok())
{
  std_msgs::Int8 msg;
std::stringstream ss;
msg.data = ui_.m_hSlider.display(int);

ROS_INFO("%d", msg.data);


if (dac==1) {
  my_publisher.publish(msg);
 }
  ros::spinOnce();
  loop_rate.sleep();
  ++count;
}

return 0;
}


void MyPlugin::shutdownPlugin()
{
}

void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
{
}

void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
{
}


} // namespace
PLUGINLIB_DECLARE_CLASS(rqt_mypkg, MyPlugin, rqt_mypkg::MyPlugin, rqt_gui_cpp::Plugin)
edit retag flag offensive close merge delete

Comments

what are the errors you get when you run catkin_make? And your formatting in the bottom is a bit off, can you please fix it so it's easier to read?

janindu gravatar image janindu  ( 2016-07-06 22:15:10 -0500 )edit

In fact I have made a lot of progress since this morning ^^ I delete this post because It's not actual. I will ask another question with my new code if I encountered new problems :)

Piero-31 gravatar image Piero-31  ( 2016-07-06 22:52:45 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2016-07-11 17:01:09 -0500

Piero-31 gravatar image

updated 2016-07-11 17:23:21 -0500

I finally succeeded. Here are my different files, I hope it will help some users.

In fact I had to create a SLOT, in which one I put a publisher to send a message containing a value. This publisher is made following the tutorial but there are differencies. The subscriber is in another file and made following the tutorial too. In the cpp file my_plugin.cpp, you can add everything you want to design your Qt interface, like new signals, slots, layout...

The "outputVal(int)" SLOT is a SLOT that enables me to put the value of the cursor in a defined variable. This variable is charged in the message in the slot "publier()".

My header file :

#ifndef rqt_mypkg__my_plugin_H
#define rqt_mypkg__my_plugin_H

#include <rqt_gui_cpp/plugin.h>
#include <rqt_mypkg/ui_my_plugin.h>
#include <QWidget>
#include <QString>
#include <QList>

#include <ros/ros.h>
#include "std_msgs/String.h"
#include <std_msgs/Int8.h>


namespace rqt_mypkg {

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_;

  ros::NodeHandle ros_node_handle_;
  ros::Publisher my_publisher_;
  ros::Subscriber my_suscriber_;


public Q_SLOTS:

  virtual void publier();
  virtual void outputVal(double val);

protected:
  int value;


};
} // namespace
#endif // rqt_mypkg_my_plugin_H

My cpp file, my_plugin.cpp :

#include "rqt_mypkg/my_plugin.h"
#include <pluginlib/class_list_macros.h>
#include "ros/ros.h"

#include <QStringList>
#include "std_msgs/String.h"
#include <sstream>
#include <std_msgs/Int8.h>


namespace rqt_mypkg {

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_);

connect(ui_.m_hSlider, SIGNAL(valueChanged(int)), this, SLOT(outputVal(int)));

connect(ui_.m_bouton, SIGNAL(clicked()), this, SLOT(publier()));

}

void MyPlugin::outputVal (int val)
{
  value = val;
}

void MyPlugin::publier ()
{

 my_publisher_ = ros_node_handle_.advertise<std_msgs::Int8>("chatter", 1000);
  if (ros::ok() && my_publisher_)
    {
      // below it is to wait forsubscriber. Otherwise the first publication will not be heard by the subscriber. 
      ros::Rate poll_rate(100);
      while(my_publisher_.getNumSubscribers() == 0)
      {
          poll_rate.sleep();
      }

      // I create my message 
      std_msgs::Int8 msg;

      msg.data = value

      my_publisher_.publish(msg);

      ROS_INFO("%d", msg.data);

      ros::spinOnce();

   }
}
void MyPlugin::shutdownPlugin()
{
}

void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
{
}

void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
{
}


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

My ui 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>741</width>
    <height>531</height>
   </rect>
  </property>
  <property name="windowTitle">
   <string>Form</string>
  </property>
  <widget class="QSlider ...
(more)
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-07-06 19:05:15 -0500

Seen: 1,568 times

Last updated: Jul 11 '16