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

There are some differences, not mentioned in http://wiki.ros.org/ROS/Tutorials/WritingServiceClient%28c%2B%2B%29). The service must be a class member of your plugin class; however, services/publishers/subscribers as class members are not so special to rqt; it's a quite common practise...

A few notes, special to rqt:

  • advertise your service in initPlugin
  • use getNodeHandle() as NodeHandle if your service can run in a single thread (with your GUI); note that long running services may block your GUI
  • use getNodeHandleMT() as NodeHandle if your service may run asynchronously with your GUI. Thread-safety? Your Job!!!
  • call service.shutDown() in shutDownPlugin(). Otherwise your service can be called after your GUI Plugin was unloaded might can cause seg fault.

Your code may look like:

Header:

#include "beginner_tutorials/AddTwoInts.h"    

  // this should be know to you
class YourRqtPlugin

  : public rqt_gui_cpp::Plugin
{

  Q_OBJECT

public:
  // this should be know to you
  YourRqtPlugin();

  virtual void initPlugin(qt_gui_cpp::PluginContext& context);

  virtual void shutdownPlugin();

protected:

      // this is new for the service
     bool add(beginner_tutorials::AddTwoInts::Request  &req,
                    beginner_tutorials::AddTwoInts::Response &res);
      // and this is new for the service
    ros::ServiceServer service;

};

Source:

YourRqtPlugin::YourRqtPlugin()  : 
  rqt_gui_cpp::Plugin()
{
  setObjectName("Qt based service server"); // or whatever
}

void YourRqtPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{  
     <<.........................>>
         other GUI intialization stuff
     <<.........................>>
      // advertise your service in initPlugin
      // use getNodeHandle() to get a nodehandle reference
     service = getNodeHandle().advertiseService("add_two_ints", &YourRqtPlugin::add, this);
}

void YourRqtPlugin::shutdownPlugin()
{
    // shutdown service; otherwise seg faults possible if service is called after plugin was unloaded
    service.shutDown();
}

bool YourRqtPlugin::add(beginner_tutorials::AddTwoInts::Request  &req,
                    beginner_tutorials::AddTwoInts::Response &res)
{

     res.sum = req.a + req.b;
     ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
     ROS_INFO("sending back response: [%ld]", (long int)res.sum);
     return true;
}

There are some differences, not mentioned in http://wiki.ros.org/ROS/Tutorials/WritingServiceClient%28c%2B%2B%29). The service must be a class member of your plugin class; however, services/publishers/subscribers as class members are not so special to rqt; it's a quite common practise...

A few notes, special to rqt:

  • advertise your service in initPlugin
  • use getNodeHandle() as NodeHandle if your service can run in a single thread (with your GUI); note that long running services may block your GUI
  • use getNodeHandleMT() as NodeHandle if your service may run asynchronously with your GUI. Thread-safety? Your Job!!!
  • call service.shutDown() in shutDownPlugin(). Otherwise your service can be called after your GUI Plugin was unloaded which might can cause seg fault.

Your code may look like:

Header:

#include "beginner_tutorials/AddTwoInts.h"    

  // this should be know to you
class YourRqtPlugin

  : public rqt_gui_cpp::Plugin
{

  Q_OBJECT

public:
  // this should be know to you
  YourRqtPlugin();

  virtual void initPlugin(qt_gui_cpp::PluginContext& context);

  virtual void shutdownPlugin();

protected:

      // this is new for the service
     bool add(beginner_tutorials::AddTwoInts::Request  &req,
                    beginner_tutorials::AddTwoInts::Response &res);
      // and this is new for the service
    ros::ServiceServer service;

};

Source:

YourRqtPlugin::YourRqtPlugin()  : 
  rqt_gui_cpp::Plugin()
{
  setObjectName("Qt based service server"); // or whatever
}

void YourRqtPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
{  
     <<.........................>>
         other GUI intialization stuff
     <<.........................>>
      // advertise your service in initPlugin
      // use getNodeHandle() to get a nodehandle reference
     service = getNodeHandle().advertiseService("add_two_ints", &YourRqtPlugin::add, this);
}

void YourRqtPlugin::shutdownPlugin()
{
    // shutdown service; otherwise seg faults possible if service is called after plugin was unloaded
    service.shutDown();
}

bool YourRqtPlugin::add(beginner_tutorials::AddTwoInts::Request  &req,
                    beginner_tutorials::AddTwoInts::Response &res)
{

     res.sum = req.a + req.b;
     ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
     ROS_INFO("sending back response: [%ld]", (long int)res.sum);
     return true;
}