service_publication.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008, Morgan Quigley and 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_SERVICE_PUBLICATION_H
00029 #define ROSCPP_SERVICE_PUBLICATION_H
00030 
00031 #include "ros/service_callback_helper.h"
00032 #include "common.h"
00033 #include "XmlRpc.h"
00034 
00035 #include <boost/thread/mutex.hpp>
00036 
00037 #include <boost/shared_ptr.hpp>
00038 #include <boost/shared_array.hpp>
00039 #include <boost/thread.hpp>
00040 #include <boost/enable_shared_from_this.hpp>
00041 
00042 #include <vector>
00043 #include <queue>
00044 
00045 namespace ros
00046 {
00047 
00048 class ServiceClientLink;
00049 typedef boost::shared_ptr<ServiceClientLink> ServiceClientLinkPtr;
00050 typedef std::vector<ServiceClientLinkPtr> V_ServiceClientLink;
00051 class CallbackQueueInterface;
00052 
00053 class Message;
00054 
00061 class ROSCPP_DECL ServicePublication : public boost::enable_shared_from_this<ServicePublication>
00062 {
00063 public:
00064   ServicePublication(const std::string& name, const std::string &md5sum, const std::string& data_type, const std::string& request_data_type,
00065                 const std::string& response_data_type, const ServiceCallbackHelperPtr& helper, CallbackQueueInterface* queue,
00066                 const VoidConstPtr& tracked_object);
00067   ~ServicePublication();
00068 
00072   void processRequest(boost::shared_array<uint8_t> buf, size_t num_bytes, const ServiceClientLinkPtr& link);
00073 
00077   void addServiceClientLink(const ServiceClientLinkPtr& link);
00081   void removeServiceClientLink(const ServiceClientLinkPtr& link);
00082 
00086   void drop();
00090   bool isDropped() { return dropped_; }
00091 
00092   const std::string& getMD5Sum() { return md5sum_; }
00093   const std::string& getRequestDataType() { return request_data_type_; }
00094   const std::string& getResponseDataType() { return response_data_type_; }
00095   const std::string& getDataType() { return data_type_; }
00096   const std::string& getName() { return name_; }
00097 
00098 private:
00099   void dropAllConnections();
00100 
00101   std::string name_;
00102   std::string md5sum_;
00103   std::string data_type_;
00104   std::string request_data_type_;
00105   std::string response_data_type_;
00106   ServiceCallbackHelperPtr helper_;
00107 
00108   V_ServiceClientLink client_links_;
00109   boost::mutex client_links_mutex_;
00110 
00111   bool dropped_;
00112 
00113   CallbackQueueInterface* callback_queue_;
00114   bool has_tracked_object_;
00115   VoidConstWPtr tracked_object_;
00116 };
00117 typedef boost::shared_ptr<ServicePublication> ServicePublicationPtr;
00118 
00119 }
00120 
00121 #endif // ROSCPP_SERVICE_PUBLICATION_H


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Thu Jun 6 2019 21:10:05