30 #include "std_msgs/String.h" 32 #include <boost/thread.hpp> 44 ROS_INFO_STREAM(
"I heard: [ " << msg->data <<
"] in thread [" << boost::this_thread::get_id() <<
"] (Main thread)");
52 ROS_INFO_STREAM(
"I heard: [ " << msg->data <<
"] in thread [" << boost::this_thread::get_id() <<
"]");
70 int main(
int argc,
char **argv)
72 ros::init(argc, argv,
"listener_with_custom_callback_processing");
107 chatter_thread.join();
ros::CallbackQueue g_queue
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void chatterCallbackCustomQueue(const std_msgs::String::ConstPtr &msg)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void spinOnce()
void chatterCallbackMainQueue(const std_msgs::String::ConstPtr &msg)
boost::shared_ptr< void > VoidPtr
int main(int argc, char **argv)