custom_callback_processing.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, 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 "ros/callback_queue.h"
00030 #include "std_msgs/String.h"
00031 
00032 #include <boost/thread.hpp>
00033 
00042 void chatterCallbackMainQueue(const std_msgs::String::ConstPtr& msg)
00043 {
00044   ROS_INFO_STREAM("I heard: [ " << msg->data << "] in thread [" << boost::this_thread::get_id() << "] (Main thread)");
00045 }
00046 
00050 void chatterCallbackCustomQueue(const std_msgs::String::ConstPtr& msg)
00051 {
00052   ROS_INFO_STREAM("I heard: [ " << msg->data << "] in thread [" << boost::this_thread::get_id() << "]");
00053 }
00054 
00058 ros::CallbackQueue g_queue;
00059 void callbackThread()
00060 {
00061   ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00062 
00063   ros::NodeHandle n;
00064   while (n.ok())
00065   {
00066     g_queue.callAvailable(ros::WallDuration(0.01));
00067   }
00068 }
00069 
00070 int main(int argc, char **argv)
00071 {
00072   ros::init(argc, argv, "listener_with_custom_callback_processing");
00073   ros::NodeHandle n;
00074 
00081   ros::SubscribeOptions ops = ros::SubscribeOptions::create<std_msgs::String>("chatter", 1000,
00082                                                                               chatterCallbackCustomQueue,
00083                                                                               ros::VoidPtr(), &g_queue);
00084   ros::Subscriber sub = n.subscribe(ops);
00085 
00089   ros::Subscriber sub2 = n.subscribe("chatter", 1000, chatterCallbackMainQueue);
00090 
00094   boost::thread chatter_thread(callbackThread);
00095 
00096   ROS_INFO_STREAM("Main thread id=" << boost::this_thread::get_id());
00100   ros::Rate r(1);
00101   while (n.ok())
00102   {
00103     ros::spinOnce();
00104     r.sleep();
00105   }
00106 
00107   chatter_thread.join();
00108 
00109   return 0;
00110 }


roscpp_tutorials
Author(s): Morgan Quigley
autogenerated on Mon Oct 6 2014 06:54:46