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/common.h>
39 #include <ros/types.h>
40 #include <boost/function.hpp>
41 #include <boost/shared_ptr.hpp>
42 #include <boost/enable_shared_from_this.hpp>
43 #include <vector>
44 
45 namespace ros
46 {
47 
48 class Transport;
50 
51 class Header;
52 
56 class ROSCPP_DECL Transport : public boost::enable_shared_from_this<Transport>
57 {
58 public:
59  Transport();
60  virtual ~Transport() {}
61 
68  virtual int32_t read(uint8_t* buffer, uint32_t size) = 0;
75  virtual int32_t write(uint8_t* buffer, uint32_t size) = 0;
76 
80  virtual void enableWrite() = 0;
84  virtual void disableWrite() = 0;
85 
89  virtual void enableRead() = 0;
93  virtual void disableRead() = 0;
94 
98  virtual void close() = 0;
99 
104  virtual const char* getType() = 0;
105 
106  typedef boost::function<void(const TransportPtr&)> Callback;
110  void setDisconnectCallback(const Callback& cb) { disconnect_cb_ = cb; }
114  void setReadCallback(const Callback& cb) { read_cb_ = cb; }
118  void setWriteCallback(const Callback& cb) { write_cb_ = cb; }
119 
123  virtual std::string getTransportInfo() = 0;
124 
128  virtual bool requiresHeader() {return true;}
129 
133  virtual void parseHeader(const Header& header) { (void)header; }
134 
135 protected:
136  Callback disconnect_cb_;
137  Callback read_cb_;
138  Callback write_cb_;
139 
143  bool isHostAllowed(const std::string &host) const;
144 
148  bool isOnlyLocalhostAllowed() const { return only_localhost_allowed_; }
149 
150 private:
152  std::vector<std::string> allowed_hosts_;
153 };
154 
155 }
156 
157 #endif // ROSCPP_TRANSPORT_H
virtual ~Transport()
Definition: transport.h:60
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory...
Definition: transport.h:56
void setReadCallback(const Callback &cb)
Set the function to call when there is data available to be read by this transport.
Definition: transport.h:114
bool isOnlyLocalhostAllowed() const
returns true if this transport is only allowed to talk to localhost
Definition: transport.h:148
Callback read_cb_
Definition: transport.h:137
void setWriteCallback(const Callback &cb)
Set the function to call when there is space available to write on this transport.
Definition: transport.h:118
boost::shared_ptr< Transport > TransportPtr
Definition: connection.h:55
virtual bool requiresHeader()
Returns a boolean to indicate if the transport mechanism is reliable or not.
Definition: transport.h:128
virtual void parseHeader(const Header &header)
Provides an opportunity for transport-specific options to come in through the header.
Definition: transport.h:133
bool only_localhost_allowed_
Definition: transport.h:151
void setDisconnectCallback(const Callback &cb)
Set the function to call when this transport has disconnected, either through a call to close()...
Definition: transport.h:110
std::vector< std::string > allowed_hosts_
Definition: transport.h:152
boost::function< void(const TransportPtr &)> Callback
Definition: transport.h:106
Callback disconnect_cb_
Definition: transport.h:136
Callback write_cb_
Definition: transport.h:138


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:26