connection.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef ROSCPP_CONNECTION_H
37 #define ROSCPP_CONNECTION_H
38 
39 #include "ros/header.h"
40 #include "common.h"
41 
42 //#include <boost/signals2.hpp>
43 
44 //#include <boost/function.hpp>
45 #include <memory>
46 //#include <boost/shared_array.hpp>
47 #include <memory>
48 #include <mutex>
49 //#include <boost/thread/recursive_mutex.hpp>
50 
51 #define READ_BUFFER_SIZE (1024*64)
52 
53 namespace roswrap
54 {
55 
56 class Transport;
57 typedef std::shared_ptr<Transport> TransportPtr;
58 class Connection;
59 typedef std::shared_ptr<Connection> ConnectionPtr;
60 typedef std::function<void(const ConnectionPtr&, const boost::shared_array<uint8_t>&, uint32_t, bool)> ReadFinishedFunc;
61 typedef std::function<void(const ConnectionPtr&)> WriteFinishedFunc;
62 
63 typedef std::function<bool(const ConnectionPtr&, const Header&)> HeaderReceivedFunc;
64 
71 class ROSCPP_DECL Connection : public std::enable_shared_from_this<Connection>
72 {
73 public:
75  {
79  };
80 
81  Connection();
82  ~Connection();
83 
87  void initialize(const TransportPtr& transport, bool is_server, const HeaderReceivedFunc& header_func);
92  void drop(DropReason reason);
93 
97  bool isDropped();
98 
102  bool isSendingHeaderError() { return sending_header_error_; }
103 
108  void sendHeaderError(const std::string& error_message);
114  void writeHeader(const M_string& key_vals, const WriteFinishedFunc& finished_callback);
115 
129  void read(uint32_t size, const ReadFinishedFunc& finished_callback);
146  void write(const boost::shared_array<uint8_t>& buffer, uint32_t size, const WriteFinishedFunc& finished_callback, bool immedate = true);
147 
148  typedef boost::signals2::signal<void(const ConnectionPtr&, DropReason reason)> DropSignal;
149  typedef std::function<void(const ConnectionPtr&, DropReason reason)> DropFunc;
153  boost::signals2::connection addDropListener(const DropFunc& slot);
154  void removeDropListener(const boost::signals2::connection& c);
155 
159  void setHeaderReceivedCallback(const HeaderReceivedFunc& func);
160 
164  const TransportPtr& getTransport() { return transport_; }
168  Header& getHeader() { return header_; }
169 
174  void setHeader(const Header& header) { header_ = header; }
175 
176  std::string getCallerId();
177  std::string getRemoteString();
178 
179 private:
183  void onReadable(const TransportPtr& transport);
187  void onWriteable(const TransportPtr& transport);
192  void onDisconnect(const TransportPtr& transport);
193 
194 
195  void onHeaderWritten(const ConnectionPtr& conn);
196  void onErrorHeaderWritten(const ConnectionPtr& conn);
197  void onHeaderLengthRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
198  void onHeaderRead(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success);
199 
204  void readTransport();
208  void writeTransport();
209 
213  bool dropped_;
220 
224  uint32_t read_filled_;
226  uint32_t read_size_;
230  boost::recursive_mutex read_mutex_;
232  bool reading_;
236  volatile uint32_t has_read_callback_;
237 
241  uint32_t write_sent_;
243  uint32_t write_size_;
248  boost::recursive_mutex write_mutex_;
250  bool writing_;
254  volatile uint32_t has_write_callback_;
255 
258 
261 
263  boost::recursive_mutex drop_mutex_;
264 
267 };
268 typedef std::shared_ptr<Connection> ConnectionPtr;
269 
270 } // namespace roswrap
271 
272 #endif // ROSCPP_CONNECTION_H
roswrap::ConnectionPtr
std::shared_ptr< Connection > ConnectionPtr
Definition: connection.h:58
roswrap::Connection::has_read_callback_
volatile uint32_t has_read_callback_
Definition: connection.h:236
roswrap::HeaderReceivedFunc
std::function< bool(const ConnectionPtr &, const Header &)> HeaderReceivedFunc
Definition: connection.h:63
roswrap::Connection::DropFunc
std::function< void(const ConnectionPtr &, DropReason reason)> DropFunc
Definition: connection.h:149
roswrap::Connection::read_size_
uint32_t read_size_
Size of the read buffer, in bytes.
Definition: connection.h:226
roswrap::ReadFinishedFunc
std::function< void(const ConnectionPtr &, const boost::shared_array< uint8_t > &, uint32_t, bool)> ReadFinishedFunc
Definition: connection.h:60
roswrap::Connection::sending_header_error_
bool sending_header_error_
If we're sending a header error we disable most other calls.
Definition: connection.h:266
roswrap::Connection::dropped_
bool dropped_
Have we dropped?
Definition: connection.h:213
roswrap::Connection::read_buffer_
boost::shared_array< uint8_t > read_buffer_
Read buffer that ends up being passed to the read callback.
Definition: connection.h:222
roswrap::M_string
std::map< std::string, std::string > M_string
Definition: datatypes.h:46
roswrap::Connection::header_
Header header_
Incoming header.
Definition: connection.h:215
roswrap::Connection::DropReason
DropReason
Definition: connection.h:74
roswrap::Connection::drop_mutex_
boost::recursive_mutex drop_mutex_
Synchronizes drop() calls.
Definition: connection.h:263
roswrap::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:250
roswrap::console::initialize
ROSCONSOLE_DECL void initialize()
Don't call this directly. Performs any required initialization/configuration. Happens automatically w...
Definition: rossimu.cpp:235
roswrap::TransportPtr
std::shared_ptr< Transport > TransportPtr
Definition: connection.h:56
roswrap::Connection::getHeader
Header & getHeader()
Get the Header associated with this connection.
Definition: connection.h:168
roswrap::Connection::drop_signal_
DropSignal drop_signal_
Signal raised when this connection is dropped.
Definition: connection.h:260
roswrap::Connection::write_size_
uint32_t write_size_
Size of the write buffer.
Definition: connection.h:243
roswrap::Connection::write_buffer_
boost::shared_array< uint8_t > write_buffer_
Buffer to write from.
Definition: connection.h:239
roswrap::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:248
roswrap::Connection::DropSignal
boost::signals2::signal< void(const ConnectionPtr &, DropReason reason)> DropSignal
Definition: connection.h:148
boost::shared_array< uint8_t >
roswrap::Connection::HeaderError
@ HeaderError
Definition: connection.h:77
roswrap::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:102
roswrap::WriteFinishedFunc
std::function< void(const ConnectionPtr &)> WriteFinishedFunc
Definition: connection.h:61
roswrap
Definition: param_modi.cpp:41
roswrap::Connection::header_written_callback_
WriteFinishedFunc header_written_callback_
Function to call when the outgoing header has finished writing.
Definition: connection.h:257
roswrap::Connection::header_func_
HeaderReceivedFunc header_func_
Function that handles the incoming header.
Definition: connection.h:219
roswrap::Connection::read_callback_
ReadFinishedFunc read_callback_
Function to call when the read is finished.
Definition: connection.h:228
roswrap::Connection::write_sent_
uint32_t write_sent_
Amount of data we've written from the write buffer.
Definition: connection.h:241
roswrap::Connection::TransportDisconnect
@ TransportDisconnect
Definition: connection.h:76
roswrap::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:230
roswrap::Connection::write_callback_
WriteFinishedFunc write_callback_
Function to call when the current write is finished.
Definition: connection.h:245
common.h
roswrap::Connection::transport_
TransportPtr transport_
Transport associated with us.
Definition: connection.h:217
sick_scan_xd_api_test.c
c
Definition: sick_scan_xd_api_test.py:445
colaa::detail::read
T read(const std::string &str)
General template which is unimplemented; implemented specializations follow below.
Definition: colaa.hpp:72
roswrap::Connection::read_filled_
uint32_t read_filled_
Amount of data currently in the read buffer, in bytes.
Definition: connection.h:224
roswrap::Header
Provides functionality to parse a connection header and retrieve values from it.
Definition: header.h:53
roswrap::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:211
sick_scan_base.h
roswrap::Connection::has_write_callback_
volatile uint32_t has_write_callback_
Definition: connection.h:254
roswrap::message_traits::header
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Definition: message_traits.h:281
roswrap::Connection::Destructing
@ Destructing
Definition: connection.h:78
ROSCPP_DECL
#define ROSCPP_DECL
Definition: roswrap/src/cfgsimu/sick_scan/ros/common.h:63
roswrap::Transport
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory,...
Definition: transport.h:56
roswrap::Connection::reading_
bool reading_
Flag telling us if we're in the middle of a read (mostly to avoid recursive deadlocking)
Definition: connection.h:232
roswrap::Connection::write_callback_mutex_
std::mutex write_callback_mutex_
Definition: connection.h:246
roswrap::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:174
roswrap::Connection::getTransport
const TransportPtr & getTransport()
Get the Transport associated with this connection.
Definition: connection.h:164
writeHeader
int writeHeader(roslz4_stream *str)
roswrap::Connection
Encapsulates a connection to a remote host, independent of the transport type.
Definition: connection.h:71


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08