subscribe_options.h
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 #ifndef ROSCPP_SUBSCRIBE_OPTIONS_H
29 #define ROSCPP_SUBSCRIBE_OPTIONS_H
30 
31 #include "ros/forwards.h"
32 #include "common.h"
33 #include "ros/transport_hints.h"
34 #include "ros/message_traits.h"
36 
37 namespace ros
38 {
39 
43 struct ROSCPP_DECL SubscribeOptions
44 {
49  : queue_size(1)
50  , callback_queue(0)
51  , allow_concurrent_callbacks(false)
52  {
53  }
54 
64  SubscribeOptions(const std::string& _topic, uint32_t _queue_size, const std::string& _md5sum, const std::string& _datatype)
65  : topic(_topic)
66  , queue_size(_queue_size)
67  , md5sum(_md5sum)
68  , datatype(_datatype)
69  , callback_queue(0)
70  , allow_concurrent_callbacks(false)
71  {}
72 
81  template<class P>
82  void initByFullCallbackType(const std::string& _topic, uint32_t _queue_size,
83  const boost::function<void (P)>& _callback,
84  const boost::function<boost::shared_ptr<typename ParameterAdapter<P>::Message>(void)>& factory_fn = DefaultMessageCreator<typename ParameterAdapter<P>::Message>())
85  {
86  typedef typename ParameterAdapter<P>::Message MessageType;
87  topic = _topic;
88  queue_size = _queue_size;
89  md5sum = message_traits::md5sum<MessageType>();
90  datatype = message_traits::datatype<MessageType>();
91  helper = boost::make_shared<SubscriptionCallbackHelperT<P> >(_callback, factory_fn);
92  }
93 
102  template<class M>
103  void init(const std::string& _topic, uint32_t _queue_size,
104  const boost::function<void (const boost::shared_ptr<M const>&)>& _callback,
105  const boost::function<boost::shared_ptr<M>(void)>& factory_fn = DefaultMessageCreator<M>())
106  {
107  typedef typename ParameterAdapter<M>::Message MessageType;
108  topic = _topic;
109  queue_size = _queue_size;
110  md5sum = message_traits::md5sum<MessageType>();
111  datatype = message_traits::datatype<MessageType>();
112  helper = boost::make_shared<SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&> >(_callback, factory_fn);
113  }
114 
115  std::string topic;
116  uint32_t queue_size;
117 
118  std::string md5sum;
119  std::string datatype;
120 
122 
124 
128 
140 
142 
153  template<class M>
154  static SubscribeOptions create(const std::string& topic, uint32_t queue_size,
155  const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
156  const VoidConstPtr& tracked_object, CallbackQueueInterface* queue)
157  {
158  SubscribeOptions ops;
159  ops.init<M>(topic, queue_size, callback);
160  ops.tracked_object = tracked_object;
161  ops.callback_queue = queue;
162  return ops;
163  }
164 };
165 
166 }
167 
168 #endif
169 
170 
transport_hints.h
md5sum
const char * md5sum()
boost::shared_ptr
forwards.h
ros
ros::SubscribeOptions::topic
std::string topic
Topic to subscribe to.
Definition: subscribe_options.h:115
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
Hints for transport type and options.
Definition: subscribe_options.h:141
ros::TransportHints
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
Definition: transport_hints.h:54
ros::SubscribeOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: subscribe_options.h:123
ros::SubscribeOptions::allow_concurrent_callbacks
bool allow_concurrent_callbacks
Definition: subscribe_options.h:127
ros::SubscribeOptions::SubscribeOptions
SubscribeOptions()
Definition: subscribe_options.h:48
subscription_callback_helper.h
ros::SubscribeOptions::SubscribeOptions
SubscribeOptions(const std::string &_topic, uint32_t _queue_size, const std::string &_md5sum, const std::string &_datatype)
Constructor.
Definition: subscribe_options.h:64
ros::SubscribeOptions::tracked_object
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this subscription.
Definition: subscribe_options.h:139
ros::SubscribeOptions::init
void init(const std::string &_topic, uint32_t _queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &_callback, const boost::function< boost::shared_ptr< M >(void)> &factory_fn=DefaultMessageCreator< M >())
Templated initialization, templated on message type. Only supports "const boost::shared_ptr<M const>&...
Definition: subscribe_options.h:103
ros::SubscribeOptions::md5sum
std::string md5sum
MD5 of the message datatype.
Definition: subscribe_options.h:118
ros::DefaultMessageCreator
message_traits.h
ros::ParameterAdapter::Message
boost::remove_reference< typename boost::remove_const< M >::type >::type Message
Definition: parameter_adapter.h:71
ros::SubscribeOptions::create
static SubscribeOptions create(const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object, CallbackQueueInterface *queue)
Templated helper function for creating an AdvertiseServiceOptions with most of its options.
Definition: subscribe_options.h:154
ros::SubscribeOptions::initByFullCallbackType
void initByFullCallbackType(const std::string &_topic, uint32_t _queue_size, const boost::function< void(P)> &_callback, const boost::function< boost::shared_ptr< typename ParameterAdapter< P >::Message >(void)> &factory_fn=DefaultMessageCreator< typename ParameterAdapter< P >::Message >())
Templated initialization, templated on callback parameter type. Supports any callback parameters supp...
Definition: subscribe_options.h:82
ros::SubscribeOptions
Encapsulates all options available for creating a Subscriber.
Definition: subscribe_options.h:43
ros::SubscribeOptions::queue_size
uint32_t queue_size
Number of incoming messages to queue up for processing (messages in excess of this queue capacity wil...
Definition: subscribe_options.h:116
datatype
const char * datatype()
ros::SubscribeOptions::datatype
std::string datatype
Datatype of the message we'd like to subscribe as.
Definition: subscribe_options.h:119
ros::SubscribeOptions::helper
SubscriptionCallbackHelperPtr helper
Helper object used to get create messages and call callbacks.
Definition: subscribe_options.h:121
ros::CallbackQueueInterface
Abstract interface for a queue used to handle all callbacks within roscpp.
Definition: callback_queue_interface.h:82


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44