advertise_options.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #ifndef ROSCPP_ADVERTISE_OPTIONS_H
00029 #define ROSCPP_ADVERTISE_OPTIONS_H
00030 
00031 #include "ros/forwards.h"
00032 #include "ros/message_traits.h"
00033 #include "common.h"
00034 
00035 namespace ros
00036 {
00037 
00041 struct ROSCPP_DECL AdvertiseOptions
00042 {
00043   AdvertiseOptions()
00044   : callback_queue(0)
00045   , latch(false)
00046   {
00047   }
00048 
00049   /*
00050    * \brief Constructor
00051    * \param _topic Topic to publish on
00052    * \param _queue_size Maximum number of outgoing messages to be queued for delivery to subscribers
00053    * \param _md5sum The md5sum of the message datatype published on this topic
00054    * \param _datatype Datatype of the message published on this topic (eg. "std_msgs/String")
00055    * \param _connect_cb Function to call when a subscriber connects to this topic
00056    * \param _disconnect_cb Function to call when a subscriber disconnects from this topic
00057    */
00058   AdvertiseOptions(const std::string& _topic, uint32_t _queue_size, const std::string& _md5sum,
00059                    const std::string& _datatype, const std::string& _message_definition,
00060                    const SubscriberStatusCallback& _connect_cb = SubscriberStatusCallback(),
00061                    const SubscriberStatusCallback& _disconnect_cb = SubscriberStatusCallback())
00062   : topic(_topic)
00063   , queue_size(_queue_size)
00064   , md5sum(_md5sum)
00065   , datatype(_datatype)
00066   , message_definition(_message_definition)
00067   , connect_cb(_connect_cb)
00068   , disconnect_cb(_disconnect_cb)
00069   , callback_queue(0)
00070   , latch(false)
00071   , has_header(false)
00072   {}
00073 
00083   template <class M>
00084   void init(const std::string& _topic, uint32_t _queue_size,
00085             const SubscriberStatusCallback& _connect_cb = SubscriberStatusCallback(),
00086             const SubscriberStatusCallback& _disconnect_cb = SubscriberStatusCallback())
00087   {
00088     topic = _topic;
00089     queue_size = _queue_size;
00090     connect_cb = _connect_cb;
00091     disconnect_cb = _disconnect_cb;
00092     md5sum = message_traits::md5sum<M>();
00093     datatype = message_traits::datatype<M>();
00094     message_definition = message_traits::definition<M>();
00095     has_header = message_traits::hasHeader<M>();
00096   }
00097 
00098   std::string topic;                                                
00099   uint32_t queue_size;                                              
00100 
00101   std::string md5sum;                                               
00102   std::string datatype;                                             
00103   std::string message_definition;                                   
00104 
00105   SubscriberStatusCallback connect_cb;                              
00106   SubscriberStatusCallback disconnect_cb;                           
00107 
00108   CallbackQueueInterface* callback_queue;                           
00109 
00120   VoidConstPtr tracked_object;
00121 
00126   bool latch;
00127 
00131   bool has_header;
00132 
00133 
00147   template<class M>
00148   static AdvertiseOptions create(const std::string& topic, uint32_t queue_size,
00149                           const SubscriberStatusCallback& connect_cb,
00150                           const SubscriberStatusCallback& disconnect_cb,
00151                           const VoidConstPtr& tracked_object,
00152                           CallbackQueueInterface* queue)
00153   {
00154     AdvertiseOptions ops;
00155     ops.init<M>(topic, queue_size, connect_cb, disconnect_cb);
00156     ops.tracked_object = tracked_object;
00157     ops.callback_queue = queue;
00158     return ops;
00159   }
00160 };
00161 
00162 
00163 }
00164 
00165 #endif


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44