listener_threaded_spin.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/ros.h"
29 #include "std_msgs/String.h"
30 
31 #include <boost/thread.hpp>
32 
38 ros::Duration d(0.01);
39 
40 class Listener
41 {
42 public:
43  void chatter1(const std_msgs::String::ConstPtr& msg)
44  {
45  ROS_INFO_STREAM("chatter1: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
46  d.sleep();
47  }
48  void chatter2(const std_msgs::String::ConstPtr& msg)
49  {
50  ROS_INFO_STREAM("chatter2: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
51  d.sleep();
52  }
53  void chatter3(const std_msgs::String::ConstPtr& msg)
54  {
55  ROS_INFO_STREAM("chatter3: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
56  d.sleep();
57  }
58 };
59 
60 void chatter4(const std_msgs::String::ConstPtr& msg)
61 {
62  ROS_INFO_STREAM("chatter4: [" << msg->data << "] [thread=" << boost::this_thread::get_id() << "]");
63  d.sleep();
64 }
65 
66 int main(int argc, char **argv)
67 {
68  ros::init(argc, argv, "listener");
70 
71  Listener l;
72  ros::Subscriber sub1 = n.subscribe("chatter", 10, &Listener::chatter1, &l);
73  ros::Subscriber sub2 = n.subscribe("chatter", 10, &Listener::chatter2, &l);
74  ros::Subscriber sub3 = n.subscribe("chatter", 10, &Listener::chatter3, &l);
75  ros::Subscriber sub4 = n.subscribe("chatter", 10, chatter4);
76 
83  ros::spin(s);
84 
85  return 0;
86 }
87 
void chatter1(const std_msgs::String::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void chatter2(const std_msgs::String::ConstPtr &msg)
XmlRpcServer s
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Duration d(0.01)
int main(int argc, char **argv)
ROSCPP_DECL void spin()
#define ROS_INFO_STREAM(args)
void chatter3(const std_msgs::String::ConstPtr &msg)
void chatter4(const std_msgs::String::ConstPtr &msg)


roscpp_tutorials
Author(s): Morgan Quigley, Dirk Thomas
autogenerated on Sun Oct 18 2020 13:09:42