Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_SUBSCRIBE_OPTIONS_H
00029 #define ROSCPP_SUBSCRIBE_OPTIONS_H
00030
00031 #include "ros/forwards.h"
00032 #include "common.h"
00033 #include "ros/transport_hints.h"
00034 #include "ros/message_traits.h"
00035 #include "subscription_callback_helper.h"
00036
00037 namespace ros
00038 {
00039
00043 struct ROSCPP_DECL SubscribeOptions
00044 {
00048 SubscribeOptions()
00049 : queue_size(1)
00050 , callback_queue(0)
00051 , allow_concurrent_callbacks(false)
00052 {
00053 }
00054
00064 SubscribeOptions(const std::string& _topic, uint32_t _queue_size, const std::string& _md5sum, const std::string& _datatype)
00065 : topic(_topic)
00066 , queue_size(_queue_size)
00067 , md5sum(_md5sum)
00068 , datatype(_datatype)
00069 , callback_queue(0)
00070 , allow_concurrent_callbacks(false)
00071 {}
00072
00081 template<class P>
00082 void initByFullCallbackType(const std::string& _topic, uint32_t _queue_size,
00083 const boost::function<void (P)>& _callback,
00084 const boost::function<boost::shared_ptr<typename ParameterAdapter<P>::Message>(void)>& factory_fn = DefaultMessageCreator<typename ParameterAdapter<P>::Message>())
00085 {
00086 typedef typename ParameterAdapter<P>::Message MessageType;
00087 topic = _topic;
00088 queue_size = _queue_size;
00089 md5sum = message_traits::md5sum<MessageType>();
00090 datatype = message_traits::datatype<MessageType>();
00091 helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<P>(_callback, factory_fn));
00092 }
00093
00102 template<class M>
00103 void init(const std::string& _topic, uint32_t _queue_size,
00104 const boost::function<void (const boost::shared_ptr<M const>&)>& _callback,
00105 const boost::function<boost::shared_ptr<M>(void)>& factory_fn = DefaultMessageCreator<M>())
00106 {
00107 typedef typename ParameterAdapter<M>::Message MessageType;
00108 topic = _topic;
00109 queue_size = _queue_size;
00110 md5sum = message_traits::md5sum<MessageType>();
00111 datatype = message_traits::datatype<MessageType>();
00112 helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&>(_callback, factory_fn));
00113 }
00114
00115 std::string topic;
00116 uint32_t queue_size;
00117
00118 std::string md5sum;
00119 std::string datatype;
00120
00121 SubscriptionCallbackHelperPtr helper;
00122
00123 CallbackQueueInterface* callback_queue;
00124
00127 bool allow_concurrent_callbacks;
00128
00139 VoidConstPtr tracked_object;
00140
00141 TransportHints transport_hints;
00142
00153 template<class M>
00154 static SubscribeOptions create(const std::string& topic, uint32_t queue_size,
00155 const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
00156 const VoidConstPtr& tracked_object, CallbackQueueInterface* queue)
00157 {
00158 SubscribeOptions ops;
00159 ops.init<M>(topic, queue_size, callback);
00160 ops.tracked_object = tracked_object;
00161 ops.callback_queue = queue;
00162 return ops;
00163 }
00164 };
00165
00166 }
00167
00168 #endif
00169
00170
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Fri Aug 28 2015 12:33:11