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

Revision history [back]

The template argument deduction fails for advertiseService when using boost::bind (see https://answers.ros.org/question/233525/template-argument-deduction-fails/), so you need to be more explicit:

#include <ros/ros.h>
#include <std_srvs/SetBool.h>

bool test2(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& resp,
    bool toggle)
{
  return true;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "node");
  ros::NodeHandle nh;
  // works without template parameters
  ros::ServiceServer service0 = nh.advertiseService("my_service0", test);
  // compile error: no matching function for call to ‘ros::NodeHandle::advertiseService...

  // ros::ServiceServer service1 = nh.advertiseService("my_service1",
  //    boost::bind(&test2, _1, _2, false));
  ros::ServiceServer service2 = nh.advertiseService<std_srvs::SetBool::Request,
      std_srvs::SetBool::Response>("my_service2",
      boost::bind(&test2, _1, _2, true));
  ros::spin();
  return 0;
}

The template argument deduction fails for advertiseService when using boost::bind (see https://answers.ros.org/question/233525/template-argument-deduction-fails/), so you need to be more explicit:

#include <ros/ros.h>
#include <std_srvs/SetBool.h>

bool test(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& resp)
{
  return true;
}

bool test2(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& resp,
    bool toggle)
{
  return true;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "node");
  ros::NodeHandle nh;
  // works without template parameters
  ros::ServiceServer service0 = nh.advertiseService("my_service0", test);
  // compile error: no matching function for call to ‘ros::NodeHandle::advertiseService...

  // ros::ServiceServer service1 = nh.advertiseService("my_service1",
  //    boost::bind(&test2, _1, _2, false));
  ros::ServiceServer service2 = nh.advertiseService<std_srvs::SetBool::Request,
      std_srvs::SetBool::Response>("my_service2",
      boost::bind(&test2, _1, _2, true));
  ros::spin();
  return 0;
}