Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef ROSCPP_TRANSPORT_TCP_H
00036 #define ROSCPP_TRANSPORT_TCP_H
00037
00038 #include <ros/types.h>
00039 #include <ros/transport/transport.h>
00040
00041 #include <boost/thread/recursive_mutex.hpp>
00042 #include "ros/io.h"
00043 #include <ros/common.h>
00044
00045 namespace ros
00046 {
00047
00048 class TransportTCP;
00049 typedef boost::shared_ptr<TransportTCP> TransportTCPPtr;
00050
00051 class PollSet;
00052
00056 class ROSCPP_DECL TransportTCP : public Transport
00057 {
00058 public:
00059 static bool s_use_keepalive_;
00060 static bool s_use_ipv6_;
00061
00062 public:
00063 enum Flags
00064 {
00065 SYNCHRONOUS = 1<<0,
00066 };
00067
00068 TransportTCP(PollSet* poll_set, int flags = 0);
00069 virtual ~TransportTCP();
00070
00077 bool connect(const std::string& host, int port);
00078
00082 std::string getClientURI();
00083
00084 typedef boost::function<void(const TransportTCPPtr&)> AcceptCallback;
00091 bool listen(int port, int backlog, const AcceptCallback& accept_cb);
00095 TransportTCPPtr accept();
00099 int getServerPort() { return server_port_; }
00100
00101 void setNoDelay(bool nodelay);
00102 void setKeepAlive(bool use, uint32_t idle, uint32_t interval, uint32_t count);
00103
00104 const std::string& getConnectedHost() { return connected_host_; }
00105 int getConnectedPort() { return connected_port_; }
00106
00107
00108 virtual int32_t read(uint8_t* buffer, uint32_t size);
00109 virtual int32_t write(uint8_t* buffer, uint32_t size);
00110
00111 virtual void enableWrite();
00112 virtual void disableWrite();
00113 virtual void enableRead();
00114 virtual void disableRead();
00115
00116 virtual void close();
00117
00118 virtual std::string getTransportInfo();
00119
00120 virtual void parseHeader(const Header& header);
00121
00122 virtual const char* getType() { return "TCPROS"; }
00123
00124 private:
00128 bool initializeSocket();
00129
00130 bool setNonBlocking();
00131
00137 bool setSocket(int sock);
00138
00139 void socketUpdate(int events);
00140
00141 socket_fd_t sock_;
00142 bool closed_;
00143 boost::recursive_mutex close_mutex_;
00144
00145 bool expecting_read_;
00146 bool expecting_write_;
00147
00148 bool is_server_;
00149 sockaddr_storage server_address_;
00150 socklen_t sa_len_;
00151
00152 int server_port_;
00153 AcceptCallback accept_cb_;
00154
00155 std::string cached_remote_host_;
00156
00157 PollSet* poll_set_;
00158 int flags_;
00159
00160 std::string connected_host_;
00161 int connected_port_;
00162 };
00163
00164 }
00165
00166 #endif // ROSCPP_TRANSPORT_TCP_H
00167
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44