Main Page
Classes
Class List
Class Members
All
Functions
Variables
Files
File List
File Members
All
a
c
d
g
m
o
Functions
a
c
m
Variables
Typedefs
custom_callback_processing
custom_callback_processing.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2009, 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 "
ros/callback_queue.h
"
30
#include "std_msgs/String.h"
31
32
#include <boost/thread.hpp>
33
42
void
chatterCallbackMainQueue
(
const
std_msgs::String::ConstPtr& msg)
43
{
44
ROS_INFO_STREAM
(
"I heard: [ "
<< msg->data <<
"] in thread ["
<< boost::this_thread::get_id() <<
"] (Main thread)"
);
45
}
46
50
void
chatterCallbackCustomQueue
(
const
std_msgs::String::ConstPtr& msg)
51
{
52
ROS_INFO_STREAM
(
"I heard: [ "
<< msg->data <<
"] in thread ["
<< boost::this_thread::get_id() <<
"]"
);
53
}
54
58
ros::CallbackQueue
g_queue
;
59
void
callbackThread
()
60
{
61
ROS_INFO_STREAM
(
"Callback thread id="
<< boost::this_thread::get_id());
62
63
ros::NodeHandle
n;
64
while
(n.
ok
())
65
{
66
g_queue
.
callAvailable
(
ros::WallDuration
(0.01));
67
}
68
}
69
70
int
main
(
int
argc,
char
**argv)
71
{
72
ros::init
(argc, argv,
"listener_with_custom_callback_processing"
);
73
ros::NodeHandle
n;
74
81
ros::SubscribeOptions
ops = ros::SubscribeOptions::create<std_msgs::String>(
"chatter"
, 1000,
82
chatterCallbackCustomQueue
,
83
ros::VoidPtr
(), &
g_queue
);
84
ros::Subscriber
sub = n.
subscribe
(ops);
85
89
ros::Subscriber
sub2 = n.
subscribe
(
"chatter"
, 1000,
chatterCallbackMainQueue
);
90
94
boost::thread chatter_thread(
callbackThread
);
95
96
ROS_INFO_STREAM
(
"Main thread id="
<< boost::this_thread::get_id());
100
ros::Rate
r(1);
101
while
(n.
ok
())
102
{
103
ros::spinOnce
();
104
r.
sleep
();
105
}
106
107
chatter_thread.join();
108
109
return
0;
110
}
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
main
int main(int argc, char **argv)
Definition:
custom_callback_processing.cpp:70
ros::spinOnce
ROSCPP_DECL void spinOnce()
callbackThread
void callbackThread()
Definition:
custom_callback_processing.cpp:59
chatterCallbackCustomQueue
void chatterCallbackCustomQueue(const std_msgs::String::ConstPtr &msg)
Definition:
custom_callback_processing.cpp:50
g_queue
ros::CallbackQueue g_queue
Definition:
custom_callback_processing.cpp:58
ros::CallbackQueue
chatterCallbackMainQueue
void chatterCallbackMainQueue(const std_msgs::String::ConstPtr &msg)
Definition:
custom_callback_processing.cpp:42
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::Rate::sleep
bool sleep()
callback_queue.h
ros::NodeHandle::ok
bool ok() const
ros::SubscribeOptions
ros::Rate
ros::WallDuration
ros::CallbackQueue::callAvailable
void callAvailable()
ros::NodeHandle
ros::Subscriber
roscpp_tutorials
Author(s): Morgan Quigley, Dirk Thomas
autogenerated on Sat Apr 12 2025 02:28:00