listener_async_spin.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
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::AsyncSpinner s(4);
00083   s.start();
00084 
00085   ros::Rate r(5);
00086   while (ros::ok())
00087   {
00088     ROS_INFO_STREAM("Main thread [" << boost::this_thread::get_id() << "].");
00089     r.sleep();
00090   }
00091 
00092   return 0;
00093 }
00094 


roscpp_tutorials
Author(s): Morgan Quigley
autogenerated on Fri Aug 28 2015 12:38:18