connection.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #ifndef ROSCPP_CONNECTION_H
00036 #define ROSCPP_CONNECTION_H
00037 
00038 #include "ros/header.h"
00039 #include "common.h"
00040 
00041 #include <boost/signals2.hpp>
00042 
00043 #include <boost/function.hpp>
00044 #include <boost/shared_ptr.hpp>
00045 #include <boost/shared_array.hpp>
00046 #include <boost/enable_shared_from_this.hpp>
00047 #include <boost/thread/mutex.hpp>
00048 #include <boost/thread/recursive_mutex.hpp>
00049 
00050 #define READ_BUFFER_SIZE (1024*64)
00051 
00052 namespace ros
00053 {
00054 
00055 class Transport;
00056 typedef boost::shared_ptr<Transport> TransportPtr;
00057 class Connection;
00058 typedef boost::shared_ptr<Connection> ConnectionPtr;
00059 typedef boost::function<void(const ConnectionPtr&, const boost::shared_array<uint8_t>&, uint32_t, bool)> ReadFinishedFunc;
00060 typedef boost::function<void(const ConnectionPtr&)> WriteFinishedFunc;
00061 
00062 typedef boost::function<bool(const ConnectionPtr&, const Header&)> HeaderReceivedFunc;
00063 
00070 class ROSCPP_DECL Connection : public boost::enable_shared_from_this<Connection>
00071 {
00072 public:
00073   enum DropReason
00074   {
00075     TransportDisconnect,
00076     HeaderError,
00077     Destructing,
00078   };
00079 
00080   Connection();
00081   ~Connection();
00082 
00086   void initialize(const TransportPtr& transport, bool is_server, const HeaderReceivedFunc& header_func);
00091   void drop(DropReason reason);
00092 
00096   bool isDropped();
00097 
00101   bool isSendingHeaderError() { return sending_header_error_; }
00102 
00107   void sendHeaderError(const std::string& error_message);
00113   void writeHeader(const M_string& key_vals, const WriteFinishedFunc& finished_callback);
00114 
00128   void read(uint32_t size, const ReadFinishedFunc& finished_callback);
00145   void write(const boost::shared_array<uint8_t>& buffer, uint32_t size, const WriteFinishedFunc& finished_callback, bool immedate = true);
00146 
00147   typedef boost::signals2::signal<void(const ConnectionPtr&, DropReason reason)> DropSignal;
00148   typedef boost::function<void(const ConnectionPtr&, DropReason reason)> DropFunc;
00152   boost::signals2::connection addDropListener(const DropFunc& slot);
00153   void removeDropListener(const boost::signals2::connection& c);
00154 
00158   void setHeaderReceivedCallback(const HeaderReceivedFunc& func);
00159 
00163   const TransportPtr& getTransport() { return transport_; }
00167   Header& getHeader() { return header_; }
00168 
00173   void setHeader(const Header& header) { header_ = header; }
00174 
00175   std::string getCallerId();
00176   std::string getRemoteString();
00177 
00178 private:
00182   void onReadable(const TransportPtr& transport);
00186   void onWriteable(const TransportPtr& transport);
00191   void onDisconnect(const TransportPtr& transport);
00192 
00193 
00194   void onHeaderWritten(const ConnectionPtr& conn);
00195   void onErrorHeaderWritten(const ConnectionPtr& conn);
00196   void onHeaderLengthRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
00197   void onHeaderRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
00198 
00203   void readTransport();
00207   void writeTransport();
00208 
00210   bool is_server_;
00212   bool dropped_;
00214   Header header_;
00216   TransportPtr transport_;
00218   HeaderReceivedFunc header_func_;
00219 
00221   boost::shared_array<uint8_t> read_buffer_;
00223   uint32_t read_filled_;
00225   uint32_t read_size_;
00227   ReadFinishedFunc read_callback_;
00229   boost::recursive_mutex read_mutex_;
00231   bool reading_;
00235   volatile uint32_t has_read_callback_;
00236 
00238   boost::shared_array<uint8_t> write_buffer_;
00240   uint32_t write_sent_;
00242   uint32_t write_size_;
00244   WriteFinishedFunc write_callback_;
00245   boost::mutex write_callback_mutex_;
00247   boost::recursive_mutex write_mutex_;
00249   bool writing_;
00253   volatile uint32_t has_write_callback_;
00254 
00256   WriteFinishedFunc header_written_callback_;
00257 
00259   DropSignal drop_signal_;
00260 
00262   boost::recursive_mutex drop_mutex_;
00263 
00265   bool sending_header_error_;
00266 };
00267 typedef boost::shared_ptr<Connection> ConnectionPtr;
00268 
00269 } // namespace ros
00270 
00271 #endif // ROSCPP_CONNECTION_H


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:46