Go to the documentation of this file.
36 #ifndef ROSCPP_TRANSPORT_TCP_H
37 #define ROSCPP_TRANSPORT_TCP_H
39 #include <ros/types.h>
40 #include <ros/transport/transport.h>
44 #include <ros/common.h>
78 bool connect(
const std::string& host,
int port);
83 std::string getClientURI();
92 bool listen(
int port,
int backlog,
const AcceptCallback& accept_cb);
103 void setNoDelay(
bool nodelay);
104 void setKeepAlive(
bool use, uint32_t idle, uint32_t interval, uint32_t count);
110 virtual int32_t
read(uint8_t* buffer, uint32_t size);
111 virtual int32_t write(uint8_t* buffer, uint32_t size);
113 virtual void enableWrite();
114 virtual void disableWrite();
115 virtual void enableRead();
116 virtual void disableRead();
118 virtual void close();
120 virtual std::string getTransportInfo();
124 virtual const char*
getType() {
return "TCPROS"; }
130 bool initializeSocket();
132 bool setNonBlocking();
139 bool setSocket(
int sock);
141 void socketUpdate(
int events);
171 #endif // ROSCPP_TRANSPORT_TCP_H
sockaddr_storage local_address_
std::string connected_host_
const std::string & getConnectedHost()
std::string cached_remote_host_
std::function< void(const TransportTCPPtr &)> AcceptCallback
sockaddr_storage server_address_
static bool s_use_keepalive_
std::shared_ptr< TransportTCP > TransportTCPPtr
int getServerPort()
Returns the port this transport is listening on.
virtual const char * getType()
Return a string that details the type of transport (Eg. TCPROS)
AcceptCallback accept_cb_
T read(const std::string &str)
General template which is unimplemented; implemented specializations follow below.
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Manages a set of sockets being polled through the poll() function call.
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory,...
boost::recursive_mutex close_mutex_
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12