(!) 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.

Receiving Messages in rosserial_windows

Description: An example of receiving messages in rosserial_windows

Keywords: rosserial, windows, rosserial_windows

Tutorial Level: INTERMEDIATE

Introduction

By now you've learned how to say Hello World with rosserial_windows. But what about if you want to receive a message? This tutorial will guide you through receiving messages in rosserial_windows

Using a Callback Function

Receiving a message is a little more complicated than sending, but only slightly. You'll need to tell the node handle what to do when you receive a message. Specifically, we'll use a callback function that gets called when a message is received.

Let's say that you want to receive the estimated pose of the robot. Whenever that happens, you'll want to print out the pose. Here's a function that might do that.

   1 void estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose)
   2 {
   3   printf ("Received pose %f, %f, %f\n", pose.pose.pose.position.x,
   4           pose.pose.pose.position.y, pose.pose.pose.position.z);
   5 }

That is an example of a callback function. It handles a new pose, in this case by printing to the screen. The next question is how do you get this called when receiving a new message? Assuming that you've already connected to the ROS master and have a NodeHandle called nh, here's how you would do that:

   1 ros::Subscriber < geometry_msgs::PoseWithCovarianceStamped > 
   2   poseSub ("estimated_pose", &estimated_pose_callback);
   3 nh.subscribe (poseSub);

Receiving Messages

Now you have a callback and you've subscribed, but if you don't actually give rosserial a chance to process messages you won't receive anything. Fortunately, we've been doing that all along. That's what this bit of code does:

   1 while (1)
   2 {
   3   nh.spinOnce ();
   4   Sleep (100);
   5 }

All this does is give rosserial a chance to process messages and then sleep for a bit. The sleep is optional, though I don't recommend just calling spinOnce(). If you have other elements that you need to call that block for short periods, put them in this loop. Otherwise, beware that going too long between calling spinOnce() will produce disconnects.

Example

Here's the full example of how to receive messages.

   1 #include "stdafx.h"
   2 #include <string>
   3 #include <stdio.h>
   4 #include "ros.h"
   5 #include <geometry_msgs/PoseWithCovarianceStamped.h>
   6 #include <windows.h>
   7 
   8 using std::string;
   9 
  10 void estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose)
  11 {
  12   printf ("Received pose %f, %f, %f\n", pose.pose.pose.position.x,
  13           pose.pose.pose.position.y, pose.pose.pose.position.z);
  14 }
  15 
  16 int _tmain (int argc, _TCHAR * argv[])
  17 {
  18   ros::NodeHandle nh;
  19   char *ros_master = "1.2.3.4";
  20 
  21   printf ("Connecting to server at %s\n", ros_master);
  22   nh.initNode (ros_master);
  23 
  24   ros::Subscriber < geometry_msgs::PoseWithCovarianceStamped > 
  25     poseSub ("estimated_pose", &estimated_pose_callback);
  26   nh.subscribe (poseSub);
  27 
  28   printf ("Waiting to receive messages\n");
  29   while (1)
  30   {
  31     nh.spinOnce ();
  32     Sleep (100);
  33   }
  34 
  35   printf ("All done!\n");
  36   return 0;
  37 }

Running it all together

Again, assuming the Husky/Gazebo simulation from ROS 101 Drive a Husky, here's how to receive the pose from odometry:

In one terminal, launch the husky simulator in an empty world:

roslaunch husky_gazebo husky_empty_world.launch

In another terminal, start the rosserial_server with the estimated_pose topic remapped to the odometry result from robot EKF:

rosrun rosserial_server socket_node estimated_pose:=/robot_pose_ekf/odom

Now run the app, and you should be receiving pose messages. If not, check that the mapping is correct, using rostopic if necessary.

Class-based Approach

It's possible to subclass the Subscriber class for a more object-oriented approach. In that case, instead of registering with the call back above simply instantiate the new class and pass that in to the subscribe call.

Wiki: rosserial_windows/Tutorials/Receiving Messages (last edited 2014-05-22 15:16:29 by KareemShehata)