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

Revision history [back]

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)

and cannot find a match in the NodeHandle class because all of the functions available there expect the srv_func function will belong to the same 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;
}

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)

and cannot find a match in the NodeHandle while NodeHandle class because all has only the prototypes that expect the srv_func parameter to belong to the same type of the functions available there expect the srv_func function will belong to the same 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;
}