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 "ros/transport_hints.h"
00033 #include "ros/message_traits.h"
00034 #include "subscription_callback_helper.h"
00035
00036 namespace ros
00037 {
00038
00042 struct SubscribeOptions
00043 {
00047 SubscribeOptions()
00048 : queue_size(1)
00049 , callback_queue(0)
00050 , allow_concurrent_callbacks(false)
00051 {
00052 }
00053
00063 SubscribeOptions(const std::string& _topic, uint32_t _queue_size, const std::string& _md5sum, const std::string& _datatype)
00064 : topic(_topic)
00065 , queue_size(_queue_size)
00066 , md5sum(_md5sum)
00067 , datatype(_datatype)
00068 , callback_queue(0)
00069 , allow_concurrent_callbacks(false)
00070 {}
00071
00080 template<class P>
00081 void initByFullCallbackType(const std::string& _topic, uint32_t _queue_size,
00082 const boost::function<void (P)>& _callback,
00083 const boost::function<boost::shared_ptr<typename ParameterAdapter<P>::Message>(void)>& factory_fn = DefaultMessageCreator<typename ParameterAdapter<P>::Message>())
00084 {
00085 typedef typename ParameterAdapter<P>::Message MessageType;
00086 topic = _topic;
00087 queue_size = _queue_size;
00088 md5sum = message_traits::md5sum<MessageType>();
00089 datatype = message_traits::datatype<MessageType>();
00090 helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<P>(_callback, factory_fn));
00091 }
00092
00101 template<class M>
00102 void init(const std::string& _topic, uint32_t _queue_size,
00103 const boost::function<void (const boost::shared_ptr<M const>&)>& _callback,
00104 const boost::function<boost::shared_ptr<M>(void)>& factory_fn = DefaultMessageCreator<M>())
00105 {
00106 typedef typename ParameterAdapter<M>::Message MessageType;
00107 topic = _topic;
00108 queue_size = _queue_size;
00109 md5sum = message_traits::md5sum<MessageType>();
00110 datatype = message_traits::datatype<MessageType>();
00111 helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&>(_callback, factory_fn));
00112 }
00113
00114 std::string topic;
00115 uint32_t queue_size;
00116
00117 std::string md5sum;
00118 std::string datatype;
00119
00120 SubscriptionCallbackHelperPtr helper;
00121
00122 CallbackQueueInterface* callback_queue;
00123
00126 bool allow_concurrent_callbacks;
00127
00138 VoidConstPtr tracked_object;
00139
00140 TransportHints transport_hints;
00141
00152 template<class M>
00153 static SubscribeOptions create(const std::string& topic, uint32_t queue_size,
00154 const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
00155 const VoidConstPtr& tracked_object, CallbackQueueInterface* queue)
00156 {
00157 SubscribeOptions ops;
00158 ops.init<M>(topic, queue_size, callback);
00159 ops.tracked_object = tracked_object;
00160 ops.callback_queue = queue;
00161 return ops;
00162 }
00163 };
00164
00165 }
00166
00167 #endif
00168
00169