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

Service with class method

asked 2015-07-26 16:11:02 -0500

anonymous user

Anonymous

I simply want to advertise a service from my main() using a class method as the callback.:

int main(int argc, char **argv){
ros::init(argc, argv, "conversion");//Init the ROS node
ros::NodeHandle nh;//Get the node handle

//My code (issue):
convert_pos2lin asd;//Create the object
ros::ServiceServer srv_ = nh.advertiseService("pos2lin", &convert_pos2lin::convert, &asd);

//The example code which works fine:
AddTwo a;
ros::ServiceServer ss = nh.advertiseService("add_two_ints", &AddTwo::add, &a);

ROS_INFO("Ready.");
ros::spin();

return 0;

Where the class method has the signature:

bool convert(scibot_control::srv_conversion::Request &req, scibot_control::srv_conversion::Response &res);

Despite reading the tutorials and such on this, i have been unable to do so. I am always met with the build error - no matching function for call to advertiseService...

edit retag flag offensive close merge delete

Comments

Please upload the whole source file somewhere like pastebin.com and also add the error log. It is a bit difficult to tell what can be the problem from the snippets you gave.

Boris gravatar image Boris  ( 2015-07-26 16:58:23 -0500 )edit
anonymous userAnonymous ( 2015-07-26 17:16:50 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-07-26 19:13:42 -0500

updated 2015-07-26 19:18:04 -0500

All versions of NodeHandle::advertiseService() function are templated (except for one) and template magic fails to deduce the right types. That happens because convert() can be found in the base class, while the object itself is of derived class. So, as I understand, compiler comes to the following substitution (Note T1 and T2):

advertiseService (const std::string &service, bool(T1::*srv_func)(MReq &, MRes &), T2 *obj)

while NodeHandle class has only the prototypes that expect the srv_func parameter to belong to the same type of object, as passed with obj, i.e.

advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)

What you can do here is explicitly cast the pointer to the base class:

ros::ServiceServer srv_ = nh.advertiseService("pos2lin", &convert_pos2lin::convert, (convert*) &asd);

To make sure virtual functions are overloaded properly (if you have any), here is a small demo based on modified AddTwoInts tutorial:

#include "ros/ros.h"
#include "roscpp_tutorials/TwoInts.h"

class Base
{
public:
  virtual bool add(roscpp_tutorials::TwoInts::Request& req,
                   roscpp_tutorials::TwoInts::Response& res)
  {
    res.sum = op(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;
  }

  virtual int op(int a, int b)
  {
    ROS_INFO("calling base op()");
    return a + b;
  }
};

class AddTwo: public Base
{
public:
  virtual int op(int a, int b)
  {
    ROS_INFO("calling derived op()");
    return a - b;
  }
};

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

  AddTwo a;
  ros::ServiceServer ss = n.advertiseService("add_two_ints", &AddTwo::add, (Base*) &a);

  ros::spin();

  return 0;
}
edit flag offensive delete link more

Comments

Yes, that was correct!

Thank you for your help - I wouldn't have considered the downcast...

anonymous userAnonymous ( 2015-07-26 21:45:54 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-07-26 16:11:02 -0500

Seen: 7,103 times

Last updated: Jul 26 '15