transport.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_TRANSPORT_H
36 #define ROSCPP_TRANSPORT_H
37 
38 #include <ros/types.h>
39 #include <boost/function.hpp>
40 #include <boost/shared_ptr.hpp>
41 #include <boost/enable_shared_from_this.hpp>
42 #include <vector>
43 
44 namespace ros
45 {
46 
47 class Transport;
49 
50 class Header;
51 
55 class Transport : public boost::enable_shared_from_this<Transport>
56 {
57 public:
58  Transport();
59  virtual ~Transport() {}
60 
67  virtual int32_t read(uint8_t* buffer, uint32_t size) = 0;
74  virtual int32_t write(uint8_t* buffer, uint32_t size) = 0;
75 
79  virtual void enableWrite() = 0;
83  virtual void disableWrite() = 0;
84 
88  virtual void enableRead() = 0;
92  virtual void disableRead() = 0;
93 
97  virtual void close() = 0;
98 
103  virtual const char* getType() = 0;
104 
105  typedef boost::function<void(const TransportPtr&)> Callback;
109  void setDisconnectCallback(const Callback& cb) { disconnect_cb_ = cb; }
113  void setReadCallback(const Callback& cb) { read_cb_ = cb; }
117  void setWriteCallback(const Callback& cb) { write_cb_ = cb; }
118 
122  virtual std::string getTransportInfo() = 0;
123 
127  virtual bool requiresHeader() {return true;}
128 
132  virtual void parseHeader(const Header& header) { (void)header; }
133 
134 protected:
135  Callback disconnect_cb_;
136  Callback read_cb_;
137  Callback write_cb_;
138 
142  bool isHostAllowed(const std::string &host) const;
143 
148 
149 private:
151  std::vector<std::string> allowed_hosts_;
152 };
153 
154 }
155 
156 #endif // ROSCPP_TRANSPORT_H
virtual void close()=0
Close this transport. Once this call has returned, writing on this transport should always return an ...
virtual const char * getType()=0
Return a string that details the type of transport (Eg. TCPROS)
virtual ~Transport()
Definition: transport.h:59
virtual int32_t write(uint8_t *buffer, uint32_t size)=0
Write a number of bytes from the supplied buffer. Not guaranteed to actually write that number of byt...
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory...
Definition: transport.h:55
void setReadCallback(const Callback &cb)
Set the function to call when there is data available to be read by this transport.
Definition: transport.h:113
bool isOnlyLocalhostAllowed() const
returns true if this transport is only allowed to talk to localhost
Definition: transport.h:147
Callback read_cb_
Definition: transport.h:136
void setWriteCallback(const Callback &cb)
Set the function to call when there is space available to write on this transport.
Definition: transport.h:117
boost::shared_ptr< Transport > TransportPtr
Definition: connection.h:55
virtual void enableWrite()=0
Enable writing on this transport. Allows derived classes to, for example, enable write polling for as...
virtual bool requiresHeader()
Returns a boolean to indicate if the transport mechanism is reliable or not.
Definition: transport.h:127
virtual void disableWrite()=0
Disable writing on this transport. Allows derived classes to, for example, disable write polling for ...
virtual void parseHeader(const Header &header)
Provides an opportunity for transport-specific options to come in through the header.
Definition: transport.h:132
virtual std::string getTransportInfo()=0
Returns a string description of both the type of transport and who the transport is connected to...
virtual void enableRead()=0
Enable reading on this transport. Allows derived classes to, for example, enable read polling for asy...
bool only_localhost_allowed_
Definition: transport.h:150
void setDisconnectCallback(const Callback &cb)
Set the function to call when this transport has disconnected, either through a call to close()...
Definition: transport.h:109
std::vector< std::string > allowed_hosts_
Definition: transport.h:151
boost::function< void(const TransportPtr &)> Callback
Definition: transport.h:105
Callback disconnect_cb_
Definition: transport.h:135
Callback write_cb_
Definition: transport.h:137
virtual int32_t read(uint8_t *buffer, uint32_t size)=0
Read a number of bytes into the supplied buffer. Not guaranteed to actually read that number of bytes...
virtual void disableRead()=0
Disable reading on this transport. Allows derived classes to, for example, disable read polling for a...
bool isHostAllowed(const std::string &host) const
returns true if the transport is allowed to connect to the host passed to it.
Definition: transport.cpp:107


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54