Note: This tutorial assumes that you have completed the previous tutorials: Writing a Simple Publisher and Subscriber, Writing a Simple Service.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Class Methods as Callbacks

Description: Most of the tutorials use functions in their examples, rather than class methods. This is because using functions is simpler, not because class methods are unsupported. This tutorial will show you how to use class methods for subscription and service callbacks.

Tutorial Level: BEGINNER

/!\ if no code snippet is shown where it's supposed to be or anything strange in the code shown, please open the link. Code snippet macro might not be working well with github, which is being investigated.

Subscriptions

Suppose you have a simple class, Listener:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/listener_class/listener_class.cpp

  35 class Listener
  36 {
  37 public:
  38   void callback(const std_msgs::String::ConstPtr& msg);
  39 };

Where the NodeHandle::subscribe() call using a function would have looked like this:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/listener/listener.cpp

  75   ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

Using a class method looks like this:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/listener_class/listener_class.cpp

  51   Listener listener;
  52   ros::Subscriber sub = n.subscribe("chatter", 1000, &Listener::callback, &listener);

Service Servers

Suppose you have a simple class, AddTwo:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/add_two_ints_server_class/add_two_ints_server_class.cpp

  31 class AddTwo
  32 {
  33 public:
  34   bool add(roscpp_tutorials::TwoInts::Request& req,
  35            roscpp_tutorials::TwoInts::Response& res);
  36 };

Where the old NodeHandle::advertiseService() call would look like:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/add_two_ints_server/add_two_ints_server.cpp

  45   ros::ServiceServer service = n.advertiseService("add_two_ints", add);

The class version looks like this:

https://raw.github.com/ros/ros_tutorials/groovy-devel/roscpp_tutorials/add_two_ints_server_class/add_two_ints_server_class.cpp

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

For the full set of subscribe(), advertiseService(), etc. overloads, see the NodeHandle class documentation

Wiki: cn/roscpp_tutorials/Tutorials/UsingClassMethodsAsCallbacks (last edited 2014-05-02 05:53:14 by flluo)