Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "ros/ros.h"
00029 #include "std_msgs/String.h"
00030
00031 #include <boost/thread.hpp>
00032
00038 ros::Duration d(0.01);
00039
00040 class Listener
00041 {
00042 public:
00043 void chatter1(const std_msgs::String::ConstPtr& msg)
00044 {
00045 ROS_INFO_STREAM("chatter1: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
00046 d.sleep();
00047 }
00048 void chatter2(const std_msgs::String::ConstPtr& msg)
00049 {
00050 ROS_INFO_STREAM("chatter2: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
00051 d.sleep();
00052 }
00053 void chatter3(const std_msgs::String::ConstPtr& msg)
00054 {
00055 ROS_INFO_STREAM("chatter3: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
00056 d.sleep();
00057 }
00058 };
00059
00060 void chatter4(const std_msgs::String::ConstPtr& msg)
00061 {
00062 ROS_INFO_STREAM("chatter4: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
00063 d.sleep();
00064 }
00065
00066 int main(int argc, char **argv)
00067 {
00068 ros::init(argc, argv, "listener");
00069 ros::NodeHandle n;
00070
00071 Listener l;
00072 ros::Subscriber sub1 = n.subscribe("chatter", 10, &Listener::chatter1, &l);
00073 ros::Subscriber sub2 = n.subscribe("chatter", 10, &Listener::chatter2, &l);
00074 ros::Subscriber sub3 = n.subscribe("chatter", 10, &Listener::chatter3, &l);
00075 ros::Subscriber sub4 = n.subscribe("chatter", 10, chatter4);
00076
00082 ros::MultiThreadedSpinner s(4);
00083 ros::spin(s);
00084
00085 return 0;
00086 }
00087