connection.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef ROSCPP_CONNECTION_H
36 #define ROSCPP_CONNECTION_H
37 
38 #include "ros/header.h"
39 #include "common.h"
40 
41 #include <boost/signals2.hpp>
42 
43 #include <boost/function.hpp>
44 #include <boost/shared_ptr.hpp>
45 #include <boost/shared_array.hpp>
46 #include <boost/enable_shared_from_this.hpp>
47 #include <boost/thread/mutex.hpp>
48 #include <boost/thread/recursive_mutex.hpp>
49 
50 #define READ_BUFFER_SIZE (1024*64)
51 
52 namespace ros
53 {
54 
55 class Transport;
57 class Connection;
59 typedef boost::function<void(const ConnectionPtr&, const boost::shared_array<uint8_t>&, uint32_t, bool)> ReadFinishedFunc;
60 typedef boost::function<void(const ConnectionPtr&)> WriteFinishedFunc;
61 
62 typedef boost::function<bool(const ConnectionPtr&, const Header&)> HeaderReceivedFunc;
63 
70 class ROSCPP_DECL Connection : public boost::enable_shared_from_this<Connection>
71 {
72 public:
74  {
78  };
79 
80  Connection();
81  ~Connection();
82 
86  void initialize(const TransportPtr& transport, bool is_server, const HeaderReceivedFunc& header_func);
91  void drop(DropReason reason);
92 
96  bool isDropped();
97 
101  bool isSendingHeaderError() { return sending_header_error_; }
102 
107  void sendHeaderError(const std::string& error_message);
113  void writeHeader(const M_string& key_vals, const WriteFinishedFunc& finished_callback);
114 
128  void read(uint32_t size, const ReadFinishedFunc& finished_callback);
145  void write(const boost::shared_array<uint8_t>& buffer, uint32_t size, const WriteFinishedFunc& finished_callback, bool immedate = true);
146 
147  typedef boost::signals2::signal<void(const ConnectionPtr&, DropReason reason)> DropSignal;
148  typedef boost::function<void(const ConnectionPtr&, DropReason reason)> DropFunc;
152  boost::signals2::connection addDropListener(const DropFunc& slot);
153  void removeDropListener(const boost::signals2::connection& c);
154 
158  void setHeaderReceivedCallback(const HeaderReceivedFunc& func);
159 
163  const TransportPtr& getTransport() { return transport_; }
167  Header& getHeader() { return header_; }
168 
173  void setHeader(const Header& header) { header_ = header; }
174 
175  std::string getCallerId();
176  std::string getRemoteString();
177 
178 private:
182  void onReadable(const TransportPtr& transport);
186  void onWriteable(const TransportPtr& transport);
191  void onDisconnect(const TransportPtr& transport);
192 
193 
194  void onHeaderWritten(const ConnectionPtr& conn);
195  void onErrorHeaderWritten(const ConnectionPtr& conn);
196  void onHeaderLengthRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
197  void onHeaderRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
198 
203  void readTransport();
207  void writeTransport();
208 
212  bool dropped_;
219 
223  uint32_t read_filled_;
225  uint32_t read_size_;
229  boost::recursive_mutex read_mutex_;
231  bool reading_;
235  volatile uint32_t has_read_callback_;
236 
240  uint32_t write_sent_;
242  uint32_t write_size_;
245  boost::mutex write_callback_mutex_;
247  boost::recursive_mutex write_mutex_;
249  bool writing_;
253  volatile uint32_t has_write_callback_;
254 
257 
260 
262  boost::recursive_mutex drop_mutex_;
263 
266 };
268 
269 } // namespace ros
270 
271 #endif // ROSCPP_CONNECTION_H
ros::Connection::getTransport
const TransportPtr & getTransport()
Get the Transport associated with this connection.
Definition: connection.h:163
ros::Connection::read_size_
uint32_t read_size_
Size of the read buffer, in bytes.
Definition: connection.h:225
ros::WriteFinishedFunc
boost::function< void(const ConnectionPtr &)> WriteFinishedFunc
Definition: connection.h:60
ros::Connection::read_buffer_
boost::shared_array< uint8_t > read_buffer_
Read buffer that ends up being passed to the read callback.
Definition: connection.h:221
ros::Connection::setHeader
void setHeader(const Header &header)
Set the Header associated with this connection (used with UDPROS, which receives the connection durin...
Definition: connection.h:173
ros::Connection::has_write_callback_
volatile uint32_t has_write_callback_
Definition: connection.h:253
ros::ReadFinishedFunc
boost::function< void(const ConnectionPtr &, const boost::shared_array< uint8_t > &, uint32_t, bool)> ReadFinishedFunc
Definition: connection.h:59
boost::shared_ptr< Transport >
ros::Connection::reading_
bool reading_
Flag telling us if we're in the middle of a read (mostly to avoid recursive deadlocking)
Definition: connection.h:231
ros::Connection::HeaderError
@ HeaderError
Definition: connection.h:76
ros::Connection::drop_signal_
DropSignal drop_signal_
Signal raised when this connection is dropped.
Definition: connection.h:259
ros
ros::Connection::write_callback_mutex_
boost::mutex write_callback_mutex_
Definition: connection.h:245
ros::Header
ros::Connection::DropSignal
boost::signals2::signal< void(const ConnectionPtr &, DropReason reason)> DropSignal
Definition: connection.h:147
ros::Connection::TransportDisconnect
@ TransportDisconnect
Definition: connection.h:75
ros::Connection::write_sent_
uint32_t write_sent_
Amount of data we've written from the write buffer.
Definition: connection.h:240
ros::Connection::is_server_
bool is_server_
Are we a server? Servers wait for clients to send a header and then send a header in response.
Definition: connection.h:210
ros::Transport
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory,...
Definition: transport.h:55
ros::Connection::read_callback_
ReadFinishedFunc read_callback_
Function to call when the read is finished.
Definition: connection.h:227
ros::Connection::read_filled_
uint32_t read_filled_
Amount of data currently in the read buffer, in bytes.
Definition: connection.h:223
ros::Connection::DropFunc
boost::function< void(const ConnectionPtr &, DropReason reason)> DropFunc
Definition: connection.h:148
ros::Connection::write_size_
uint32_t write_size_
Size of the write buffer.
Definition: connection.h:242
ros::Connection::sending_header_error_
bool sending_header_error_
If we're sending a header error we disable most other calls.
Definition: connection.h:265
ros::Connection
Encapsulates a connection to a remote host, independent of the transport type.
Definition: connection.h:70
ros::Connection::writing_
bool writing_
Flag telling us if we're in the middle of a write (mostly used to avoid recursive deadlocking)
Definition: connection.h:249
ros::Connection::dropped_
bool dropped_
Have we dropped?
Definition: connection.h:212
ros::Connection::drop_mutex_
boost::recursive_mutex drop_mutex_
Synchronizes drop() calls.
Definition: connection.h:262
boost::shared_array< uint8_t >
ros::Connection::header_func_
HeaderReceivedFunc header_func_
Function that handles the incoming header.
Definition: connection.h:218
ros::Connection::read_mutex_
boost::recursive_mutex read_mutex_
Mutex used for protecting reading. Recursive because a read can immediately cause another read throug...
Definition: connection.h:229
ros::Connection::DropReason
DropReason
Definition: connection.h:73
ros::ConnectionPtr
boost::shared_ptr< Connection > ConnectionPtr
Definition: connection.h:57
ros::Connection::Destructing
@ Destructing
Definition: connection.h:77
ros::Connection::write_buffer_
boost::shared_array< uint8_t > write_buffer_
Buffer to write from.
Definition: connection.h:238
ros::Connection::isSendingHeaderError
bool isSendingHeaderError()
Returns true if we're currently sending a header error (and will be automatically dropped when it's f...
Definition: connection.h:101
ros::Connection::has_read_callback_
volatile uint32_t has_read_callback_
Definition: connection.h:235
ros::Connection::write_callback_
WriteFinishedFunc write_callback_
Function to call when the current write is finished.
Definition: connection.h:244
ros::Connection::transport_
TransportPtr transport_
Transport associated with us.
Definition: connection.h:216
ros::Connection::header_written_callback_
WriteFinishedFunc header_written_callback_
Function to call when the outgoing header has finished writing.
Definition: connection.h:256
ros::Connection::getHeader
Header & getHeader()
Get the Header associated with this connection.
Definition: connection.h:167
ros::HeaderReceivedFunc
boost::function< bool(const ConnectionPtr &, const Header &)> HeaderReceivedFunc
Definition: connection.h:62
initialize
ROSCONSOLE_DECL void initialize()
header.h
ros::TransportPtr
boost::shared_ptr< Transport > TransportPtr
Definition: connection.h:55
ros::Connection::header_
Header header_
Incoming header.
Definition: connection.h:214
header
const std::string header
ros::Connection::write_mutex_
boost::recursive_mutex write_mutex_
Mutex used for protecting writing. Recursive because a write can immediately cause another write thro...
Definition: connection.h:247
ros::M_string
std::map< std::string, std::string > M_string


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44