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

Revision history [back]

click to hide/show revision 1
initial version

You are createing a local subscriber in your function call back:

void ccgui::clickLabelhelpBtn_timeout(){
this->deactiveSpeechCommand("move");
ros::Subscriber sub = getNodeHandle().subscribe("/speech_control_interface/cmd", 10, &ccgui::receiveSpeechCommand, this);
ROS_INFO("topics %s %d", sub.getTopic().c_str(), sub.getNumPublishers());
// int ret = QMessageBox::information(widget_, QString("About timeout"),
// QString("Timeout between two commands.\n"
// "in [ms]"),
// QMessageBox::Close);
}

sub is destructed and deleted from stack when the at the end function's code; thereby the subscriber is also shut down and the callback will never be called!

To solve this do the following:

Declare your subscriber somewhere in the header file:

class ccgui
: public rqt_gui_cpp::Plugin
{
Q_OBJECT
public:
<..............>

private:
Ui_Form ui_;
ros::Subcriber sub;
<....................>
}

Then subscribe as you did but without declaring the object

void ccgui::clickLabelhelpBtn_timeout(){
this->deactiveSpeechCommand("move");
sub = getNodeHandle().subscribe("/speech_control_interface/cmd", 10, &ccgui::receiveSpeechCommand, this);
ROS_INFO("topics %s %d", sub.getTopic().c_str(), sub.getNumPublishers());
// int ret = QMessageBox::information(widget_, QString("About timeout"),
// QString("Timeout between two commands.\n"
// "in [ms]"),
// QMessageBox::Close);
}

and shut it down somewhere, at the latest in plugin shutdown() (this is important because the nodehandle your retrieved by getNodeHandle) might live longer than your plugin so if you do not shut down the subscriber your callback might even be called after your plugin was shut down!!

void ccgui::shutdownPlugin()
{
   sub.shutdown();
}