Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add class member method callback support for Service Server. #282

Conversation

@romainreignier
Copy link
Contributor

romainreignier commented Apr 22, 2017

Based on the work done for the Subscriber (#241).

I did not manage to add test because there are conflicts with the full Ros version.

Here is a simple test for Arduino:

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

ros::NodeHandle  nh;
using std_srvs::SetBool;

class MyClass
{
  public:
    static void callback_class_static(const SetBool::Request& req, SetBool::Response& res)
    {
      res.success = true;
      if (req.data == true)
        res.message = "Class static method: true";
      else
        res.message = "Class static method: false";
    }

    void callback_class(const SetBool::Request& req, SetBool::Response& res)
    {
      res.success = true;
      if (req.data == true)
        res.message = "Class method: true";
      else
        res.message = "Class method: false";
    }
};

MyClass mc;

void callback_non_class(const SetBool::Request& req, SetBool::Response& res)
{
  res.success = true;
  if (req.data == true)
    res.message = "Non-class: true";
  else
    res.message = "Non-class: false";
}

ros::ServiceServer<SetBool::Request, SetBool::Response> server_non_class("non_class_srv", &callback_non_class);
ros::ServiceServer<SetBool::Request, SetBool::Response> server_class_static("class_static_srv", &MyClass::callback_class_static);
ros::ServiceServer<SetBool::Request, SetBool::Response, MyClass> server_class("class_srv", &MyClass::callback_class, &mc);

void setup()
{
  nh.initNode();
  nh.advertiseService(server_non_class);
  nh.advertiseService(server_class_static);
  nh.advertiseService(server_class);
}

void loop()
{
  nh.spinOnce();
  delay(10);
}
Based on the work done for the Subscriber (#241).
@mikepurvis

This comment has been minimized.

Copy link
Member

mikepurvis commented Apr 24, 2017

I dig it. Thanks for contributing this!

@mikepurvis mikepurvis merged commit 547c4c4 into ros-drivers:jade-devel Apr 24, 2017
1 check passed
1 check passed
continuous-integration/travis-ci/pr The Travis CI build passed
Details
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
2 participants
You can’t perform that action at this time.