35 #ifndef ROSCPP_TRANSPORT_TCP_H 36 #define ROSCPP_TRANSPORT_TCP_H 41 #include <boost/thread/recursive_mutex.hpp> 43 #include <ros/common.h> 77 bool connect(
const std::string& host,
int port);
82 std::string getClientURI();
91 bool listen(
int port,
int backlog,
const AcceptCallback& accept_cb);
95 TransportTCPPtr accept();
102 void setNoDelay(
bool nodelay);
103 void setKeepAlive(
bool use, uint32_t idle, uint32_t interval, uint32_t count);
109 virtual int32_t read(uint8_t* buffer, uint32_t size);
110 virtual int32_t write(uint8_t* buffer, uint32_t size);
112 virtual void enableWrite();
113 virtual void disableWrite();
114 virtual void enableRead();
115 virtual void disableRead();
117 virtual void close();
119 virtual std::string getTransportInfo();
123 virtual const char*
getType() {
return "TCPROS"; }
129 bool initializeSocket();
131 bool setNonBlocking();
138 bool setSocket(
int sock);
140 void socketUpdate(
int events);
170 #endif // ROSCPP_TRANSPORT_TCP_H
boost::function< void(const TransportTCPPtr &)> AcceptCallback
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory...
virtual const char * getType()
Return a string that details the type of transport (Eg. TCPROS)
std::string connected_host_
Manages a set of sockets being polled through the poll() function call.
std_msgs::Header * header(M &m)
std::string cached_remote_host_
AcceptCallback accept_cb_
boost::recursive_mutex close_mutex_
sockaddr_storage server_address_
sockaddr_storage local_address_
int getServerPort()
Returns the port this transport is listening on.
static bool s_use_keepalive_
boost::shared_ptr< TransportTCP > TransportTCPPtr
const std::string & getConnectedHost()