transport_tcp.cpp
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 #include "ros/io.h"
37 #include "ros/poll_set.h"
38 #include "ros/header.h"
39 #include "ros/file_log.h"
40 #include <ros/assert.h>
41 #include <sstream>
42 #include <boost/bind.hpp>
43 #include <fcntl.h>
44 #include <errno.h>
45 namespace ros
46 {
47 
49 bool TransportTCP::s_use_ipv6_ = false;
50 
51 TransportTCP::TransportTCP(PollSet* poll_set, int flags)
52 : sock_(ROS_INVALID_SOCKET)
53 , closed_(false)
54 , expecting_read_(false)
55 , expecting_write_(false)
56 , is_server_(false)
57 , server_port_(-1)
58 , local_port_(-1)
59 , poll_set_(poll_set)
60 , flags_(flags)
61 {
62 
63 }
64 
66 {
67  ROS_ASSERT_MSG(sock_ == -1, "TransportTCP socket [%d] was never closed", sock_);
68 }
69 
71 {
72  sock_ = sock;
73  return initializeSocket();
74 }
75 
77 {
78  if (!(flags_ & SYNCHRONOUS))
79  {
80  int result = set_non_blocking(sock_);
81  if ( result != 0 ) {
82  ROS_ERROR("setting socket [%d] as non_blocking failed with error [%d]", sock_, result);
83  close();
84  return false;
85  }
86  }
87 
88  return true;
89 }
90 
92 {
94 
95  if (!setNonBlocking())
96  {
97  return false;
98  }
99 
100  setKeepAlive(s_use_keepalive_, 60, 10, 9);
101 
102  // connect() will set cached_remote_host_ because it already has the host/port available
103  if (cached_remote_host_.empty())
104  {
105  if (is_server_)
106  {
107  cached_remote_host_ = "TCPServer Socket";
108  }
109  else
110  {
111  std::stringstream ss;
112  ss << getClientURI() << " on socket " << sock_;
113  cached_remote_host_ = ss.str();
114  }
115  }
116 
117  if (local_port_ < 0)
118  {
119  la_len_ = s_use_ipv6_ ? sizeof(sockaddr_in6) : sizeof(sockaddr_in);
120  getsockname(sock_, (sockaddr *)&local_address_, &la_len_);
121  switch (local_address_.ss_family)
122  {
123  case AF_INET:
124  local_port_ = ntohs(((sockaddr_in *)&local_address_)->sin_port);
125  break;
126  case AF_INET6:
127  local_port_ = ntohs(((sockaddr_in6 *)&local_address_)->sin6_port);
128  break;
129  }
130  }
131 
132 #ifdef ROSCPP_USE_TCP_NODELAY
133  setNoDelay(true);
134 #endif
135 
137  if (poll_set_)
138  {
139  ROS_DEBUG("Adding tcp socket [%d] to pollset", sock_);
140  poll_set_->addSocket(sock_, boost::bind(&TransportTCP::socketUpdate, this, _1), shared_from_this());
141  }
142 
143  if (!(flags_ & SYNCHRONOUS))
144  {
145  //enableRead();
146  }
147 
148  return true;
149 }
150 
152 {
153  std::string nodelay;
154  if (header.getValue("tcp_nodelay", nodelay) && nodelay == "1")
155  {
156  ROSCPP_LOG_DEBUG("Setting nodelay on socket [%d]", sock_);
157  setNoDelay(true);
158  }
159 }
160 
161 void TransportTCP::setNoDelay(bool nodelay)
162 {
163  int flag = nodelay ? 1 : 0;
164  int result = setsockopt(sock_, IPPROTO_TCP, TCP_NODELAY, (char *) &flag, sizeof(int));
165  if (result < 0)
166  {
167  ROS_ERROR("setsockopt failed to set TCP_NODELAY on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
168  }
169 }
170 
171 void TransportTCP::setKeepAlive(bool use, uint32_t idle, uint32_t interval, uint32_t count)
172 {
173  if (use)
174  {
175  int val = 1;
176  if (setsockopt(sock_, SOL_SOCKET, SO_KEEPALIVE, reinterpret_cast<const char*>(&val), sizeof(val)) != 0)
177  {
178  ROS_DEBUG("setsockopt failed to set SO_KEEPALIVE on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
179  }
180 
181 /* cygwin SOL_TCP does not seem to support TCP_KEEPIDLE, TCP_KEEPINTVL, TCP_KEEPCNT */
182 #if defined(SOL_TCP) && defined(TCP_KEEPIDLE)
183  val = idle;
184  if (setsockopt(sock_, SOL_TCP, TCP_KEEPIDLE, &val, sizeof(val)) != 0)
185  {
186  ROS_DEBUG("setsockopt failed to set TCP_KEEPIDLE on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
187  }
188 #endif
189 
190 #if defined(SOL_TCP) && defined(TCP_KEEPINTVL)
191  val = interval;
192  if (setsockopt(sock_, SOL_TCP, TCP_KEEPINTVL, &val, sizeof(val)) != 0)
193  {
194  ROS_DEBUG("setsockopt failed to set TCP_KEEPINTVL on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
195  }
196 #endif
197 
198 #if defined(SOL_TCP) && defined(TCP_KEEPCNT)
199  val = count;
200  if (setsockopt(sock_, SOL_TCP, TCP_KEEPCNT, &val, sizeof(val)) != 0)
201  {
202  ROS_DEBUG("setsockopt failed to set TCP_KEEPCNT on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
203  }
204 #endif
205  }
206  else
207  {
208  int val = 0;
209  if (setsockopt(sock_, SOL_SOCKET, SO_KEEPALIVE, reinterpret_cast<const char*>(&val), sizeof(val)) != 0)
210  {
211  ROS_DEBUG("setsockopt failed to set SO_KEEPALIVE on socket [%d] [%s]", sock_, cached_remote_host_.c_str());
212  }
213  }
214 }
215 
216 bool TransportTCP::connect(const std::string& host, int port)
217 {
218  if (!isHostAllowed(host))
219  return false; // adios amigo
220 
221  sock_ = socket(s_use_ipv6_ ? AF_INET6 : AF_INET, SOCK_STREAM, 0);
222  connected_host_ = host;
223  connected_port_ = port;
224 
225  if (sock_ == ROS_INVALID_SOCKET)
226  {
227  ROS_ERROR("socket() failed with error [%s]", last_socket_error_string());
228  return false;
229  }
230 
231  setNonBlocking();
232 
233  sockaddr_storage sas;
234  socklen_t sas_len;
235 
236  in_addr ina;
237  in6_addr in6a;
238  if (inet_pton(AF_INET, host.c_str(), &ina) == 1)
239  {
240  sockaddr_in *address = (sockaddr_in*) &sas;
241  sas_len = sizeof(sockaddr_in);
242 
243  la_len_ = sizeof(sockaddr_in);
244  address->sin_family = AF_INET;
245  address->sin_port = htons(port);
246  address->sin_addr.s_addr = ina.s_addr;
247  }
248  else if (inet_pton(AF_INET6, host.c_str(), &in6a) == 1)
249  {
250  sockaddr_in6 *address = (sockaddr_in6*) &sas;
251  sas_len = sizeof(sockaddr_in6);
252  la_len_ = sizeof(sockaddr_in6);
253  address->sin6_family = AF_INET6;
254  address->sin6_port = htons(port);
255  memcpy(address->sin6_addr.s6_addr, in6a.s6_addr, sizeof(in6a.s6_addr));
256  }
257  else
258  {
259  struct addrinfo* addr;
260  struct addrinfo hints;
261  memset(&hints, 0, sizeof(hints));
262  hints.ai_family = AF_UNSPEC;
263 
264  if (getaddrinfo(host.c_str(), NULL, &hints, &addr) != 0)
265  {
266  close();
267  ROS_ERROR("couldn't resolve publisher host [%s]", host.c_str());
268  return false;
269  }
270 
271  bool found = false;
272  struct addrinfo* it = addr;
273  char namebuf[128];
274  for (; it; it = it->ai_next)
275  {
276  if (!s_use_ipv6_ && it->ai_family == AF_INET)
277  {
278  sockaddr_in *address = (sockaddr_in*) &sas;
279  sas_len = sizeof(*address);
280 
281  memcpy(address, it->ai_addr, it->ai_addrlen);
282  address->sin_family = it->ai_family;
283  address->sin_port = htons(port);
284 
285  strcpy(namebuf, inet_ntoa(address->sin_addr));
286  found = true;
287  break;
288  }
289  if (s_use_ipv6_ && it->ai_family == AF_INET6)
290  {
291  sockaddr_in6 *address = (sockaddr_in6*) &sas;
292  sas_len = sizeof(*address);
293 
294  memcpy(address, it->ai_addr, it->ai_addrlen);
295  address->sin6_family = it->ai_family;
296  address->sin6_port = htons((u_short) port);
297 
298  // TODO IPV6: does inet_ntop need other includes for Windows?
299  inet_ntop(AF_INET6, (void*)&(address->sin6_addr), namebuf, sizeof(namebuf));
300  found = true;
301  break;
302  }
303  }
304 
305  freeaddrinfo(addr);
306 
307  if (!found)
308  {
309  ROS_ERROR("Couldn't resolve an address for [%s]\n", host.c_str());
310  return false;
311  }
312 
313  ROSCPP_LOG_DEBUG("Resolved publisher host [%s] to [%s] for socket [%d]", host.c_str(), namebuf, sock_);
314  }
315 
316  int ret = ::connect(sock_, (sockaddr*) &sas, sas_len);
317  // windows might need some time to sleep (input from service robotics hack) add this if testing proves it is necessary.
318  // ROS_ASSERT((flags_ & SYNCHRONOUS) || ret != 0);
319  if (((flags_ & SYNCHRONOUS) && ret != 0) || // synchronous, connect() should return 0
320  (!(flags_ & SYNCHRONOUS) && ret != 0 && last_socket_error() != ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN))
321  // asynchronous, connect() may return 0 or -1. When return -1, WSAGetLastError()=WSAEWOULDBLOCK/errno=EINPROGRESS
322  {
323  ROSCPP_CONN_LOG_DEBUG("Connect to tcpros publisher [%s:%d] failed with error [%d, %s]", host.c_str(), port, ret, last_socket_error_string());
324  close();
325 
326  return false;
327  }
328 
329  // from daniel stonier:
330 #ifdef WIN32
331  // This is hackish, but windows fails at recv() if its slow to connect (e.g. happens with wireless)
332  // recv() needs to check if its connected or not when its asynchronous?
333  Sleep(100);
334 #endif
335 
336 
337  std::stringstream ss;
338  ss << host << ":" << port << " on socket " << sock_;
339  cached_remote_host_ = ss.str();
340 
341  if (!initializeSocket())
342  {
343  return false;
344  }
345 
346  if (flags_ & SYNCHRONOUS)
347  {
348  ROSCPP_CONN_LOG_DEBUG("connect() succeeded to [%s:%d] on socket [%d]", host.c_str(), port, sock_);
349  }
350  else
351  {
352  ROSCPP_CONN_LOG_DEBUG("Async connect() in progress to [%s:%d] on socket [%d]", host.c_str(), port, sock_);
353  }
354 
355  return true;
356 }
357 
358 bool TransportTCP::listen(int port, int backlog, const AcceptCallback& accept_cb)
359 {
360  is_server_ = true;
361  accept_cb_ = accept_cb;
362 
363  if (s_use_ipv6_)
364  {
365  sock_ = socket(AF_INET6, SOCK_STREAM, 0);
366  sockaddr_in6 *address = (sockaddr_in6 *)&server_address_;
367  address->sin6_family = AF_INET6;
368  address->sin6_addr = isOnlyLocalhostAllowed() ?
369  in6addr_loopback :
370  in6addr_any;
371  address->sin6_port = htons(port);
372  sa_len_ = sizeof(sockaddr_in6);
373  }
374  else
375  {
376  sock_ = socket(AF_INET, SOCK_STREAM, 0);
377  sockaddr_in *address = (sockaddr_in *)&server_address_;
378  address->sin_family = AF_INET;
379  address->sin_addr.s_addr = isOnlyLocalhostAllowed() ?
380  htonl(INADDR_LOOPBACK) :
381  INADDR_ANY;
382  address->sin_port = htons(port);
383  sa_len_ = sizeof(sockaddr_in);
384  }
385 
386  if (sock_ <= 0)
387  {
388  ROS_ERROR("socket() failed with error [%s]", last_socket_error_string());
389  return false;
390  }
391 
392 
393  if (bind(sock_, (sockaddr *)&server_address_, sa_len_) < 0)
394  {
395  ROS_ERROR("bind() failed with error [%s]", last_socket_error_string());
396  return false;
397  }
398 
399  ::listen(sock_, backlog);
400  getsockname(sock_, (sockaddr *)&server_address_, &sa_len_);
401 
402  switch (server_address_.ss_family)
403  {
404  case AF_INET:
405  server_port_ = ntohs(((sockaddr_in *)&server_address_)->sin_port);
406  break;
407  case AF_INET6:
408  server_port_ = ntohs(((sockaddr_in6 *)&server_address_)->sin6_port);
409  break;
410  }
411 
412  if (!initializeSocket())
413  {
414  return false;
415  }
416 
417  if (!(flags_ & SYNCHRONOUS))
418  {
419  enableRead();
420  }
421 
422  return true;
423 }
424 
426 {
427  Callback disconnect_cb;
428 
429  if (!closed_)
430  {
431  {
432  boost::recursive_mutex::scoped_lock lock(close_mutex_);
433 
434  if (!closed_)
435  {
436  closed_ = true;
437 
439 
440  if (poll_set_)
441  {
443  }
444 
446  if ( close_socket(sock_) != 0 )
447  {
448  ROS_ERROR("Error closing socket [%d]: [%s]", sock_, last_socket_error_string());
449  } else
450  {
451  ROSCPP_LOG_DEBUG("TCP socket [%d] closed", sock_);
452  }
454 
455  disconnect_cb = disconnect_cb_;
456 
458  read_cb_ = Callback();
459  write_cb_ = Callback();
461  }
462  }
463  }
464 
465  if (disconnect_cb)
466  {
467  disconnect_cb(shared_from_this());
468  }
469 }
470 
471 int32_t TransportTCP::read(uint8_t* buffer, uint32_t size)
472 {
473  {
474  boost::recursive_mutex::scoped_lock lock(close_mutex_);
475 
476  if (closed_)
477  {
478  ROSCPP_LOG_DEBUG("Tried to read on a closed socket [%d]", sock_);
479  return -1;
480  }
481  }
482 
483  ROS_ASSERT(size > 0);
484 
485  // never read more than INT_MAX since this is the maximum we can report back with the current return type
486  uint32_t read_size = std::min(size, static_cast<uint32_t>(INT_MAX));
487  int num_bytes = ::recv(sock_, reinterpret_cast<char*>(buffer), read_size, 0);
488  if (num_bytes < 0)
489  {
490  if ( !last_socket_error_is_would_block() ) // !WSAWOULDBLOCK / !EAGAIN && !EWOULDBLOCK
491  {
492  ROSCPP_LOG_DEBUG("recv() on socket [%d] failed with error [%s]", sock_, last_socket_error_string());
493  close();
494  }
495  else
496  {
497  num_bytes = 0;
498  }
499  }
500  else if (num_bytes == 0)
501  {
502  ROSCPP_LOG_DEBUG("Socket [%d] received 0/%u bytes, closing", sock_, size);
503  close();
504  return -1;
505  }
506 
507  return num_bytes;
508 }
509 
510 int32_t TransportTCP::write(uint8_t* buffer, uint32_t size)
511 {
512  {
513  boost::recursive_mutex::scoped_lock lock(close_mutex_);
514 
515  if (closed_)
516  {
517  ROSCPP_LOG_DEBUG("Tried to write on a closed socket [%d]", sock_);
518  return -1;
519  }
520  }
521 
522  ROS_ASSERT(size > 0);
523 
524  // never write more than INT_MAX since this is the maximum we can report back with the current return type
525  uint32_t writesize = std::min(size, static_cast<uint32_t>(INT_MAX));
526  int num_bytes = ::send(sock_, reinterpret_cast<const char*>(buffer), writesize, 0);
527  if (num_bytes < 0)
528  {
530  {
531  ROSCPP_LOG_DEBUG("send() on socket [%d] failed with error [%s]", sock_, last_socket_error_string());
532  close();
533  }
534  else
535  {
536  num_bytes = 0;
537  }
538  }
539 
540  return num_bytes;
541 }
542 
544 {
546 
547  {
548  boost::recursive_mutex::scoped_lock lock(close_mutex_);
549 
550  if (closed_)
551  {
552  return;
553  }
554  }
555 
556  if (!expecting_read_)
557  {
558  poll_set_->addEvents(sock_, POLLIN);
559  expecting_read_ = true;
560  }
561 }
562 
564 {
566 
567  {
568  boost::recursive_mutex::scoped_lock lock(close_mutex_);
569 
570  if (closed_)
571  {
572  return;
573  }
574  }
575 
576  if (expecting_read_)
577  {
578  poll_set_->delEvents(sock_, POLLIN);
579  expecting_read_ = false;
580  }
581 }
582 
584 {
586 
587  {
588  boost::recursive_mutex::scoped_lock lock(close_mutex_);
589 
590  if (closed_)
591  {
592  return;
593  }
594  }
595 
596  if (!expecting_write_)
597  {
598  poll_set_->addEvents(sock_, POLLOUT);
599  expecting_write_ = true;
600  }
601 }
602 
604 {
606 
607  {
608  boost::recursive_mutex::scoped_lock lock(close_mutex_);
609 
610  if (closed_)
611  {
612  return;
613  }
614  }
615 
616  if (expecting_write_)
617  {
618  poll_set_->delEvents(sock_, POLLOUT);
619  expecting_write_ = false;
620  }
621 }
622 
624 {
626 
627  sockaddr client_address;
628  socklen_t len = sizeof(client_address);
629  int new_sock = ::accept(sock_, (sockaddr *)&client_address, &len);
630  if (new_sock >= 0)
631  {
632  ROSCPP_LOG_DEBUG("Accepted connection on socket [%d], new socket [%d]", sock_, new_sock);
633 
634  TransportTCPPtr transport(boost::make_shared<TransportTCP>(poll_set_, flags_));
635  if (!transport->setSocket(new_sock))
636  {
637  ROS_ERROR("Failed to set socket on transport for socket %d", new_sock);
638  }
639 
640  return transport;
641  }
642  else
643  {
644  ROS_ERROR("accept() on socket [%d] failed with error [%s]", sock_, last_socket_error_string());
645  }
646 
647  return TransportTCPPtr();
648 }
649 
651 {
652  {
653  boost::recursive_mutex::scoped_lock lock(close_mutex_);
654  if (closed_)
655  {
656  return;
657  }
658 
659  // Handle read events before err/hup/nval, since there may be data left on the wire
660  if ((events & POLLIN) && expecting_read_)
661  {
662  if (is_server_)
663  {
664  // Should not block here, because poll() said that it's ready
665  // for reading
666  TransportTCPPtr transport = accept();
667  if (transport)
668  {
670  accept_cb_(transport);
671  }
672  }
673  else
674  {
675  if (read_cb_)
676  {
677  read_cb_(shared_from_this());
678  }
679  }
680  }
681 
682  if ((events & POLLOUT) && expecting_write_)
683  {
684  if (write_cb_)
685  {
686  write_cb_(shared_from_this());
687  }
688  }
689  }
690 
691  if((events & POLLERR) ||
692  (events & POLLHUP) ||
693  (events & POLLNVAL))
694  {
695  uint32_t error = -1;
696  socklen_t len = sizeof(error);
697  if (getsockopt(sock_, SOL_SOCKET, SO_ERROR, reinterpret_cast<char*>(&error), &len) < 0)
698  {
699  ROSCPP_LOG_DEBUG("getsockopt failed on socket [%d]", sock_);
700  }
701  #ifdef _MSC_VER
702  char err[60];
703  strerror_s(err,60,error);
704  ROSCPP_LOG_DEBUG("Socket %d closed with (ERR|HUP|NVAL) events %d: %s", sock_, events, err);
705  #else
706  ROSCPP_LOG_DEBUG("Socket %d closed with (ERR|HUP|NVAL) events %d: %s", sock_, events, strerror(error));
707  #endif
708 
709  close();
710  }
711 }
712 
714 {
715  std::stringstream str;
716  str << "TCPROS connection on port " << local_port_ << " to [" << cached_remote_host_ << "]";
717  return str.str();
718 }
719 
721 {
723 
724  sockaddr_storage sas;
725  socklen_t sas_len = sizeof(sas);
726  getpeername(sock_, (sockaddr *)&sas, &sas_len);
727 
728  sockaddr_in *sin = (sockaddr_in *)&sas;
729  sockaddr_in6 *sin6 = (sockaddr_in6 *)&sas;
730 
731  char namebuf[128];
732  int port;
733 
734  switch (sas.ss_family)
735  {
736  case AF_INET:
737  port = ntohs(sin->sin_port);
738  strcpy(namebuf, inet_ntoa(sin->sin_addr));
739  break;
740  case AF_INET6:
741  port = ntohs(sin6->sin6_port);
742  inet_ntop(AF_INET6, (void*)&(sin6->sin6_addr), namebuf, sizeof(namebuf));
743  break;
744  default:
745  namebuf[0] = 0;
746  port = 0;
747  break;
748  }
749 
750  std::string ip = namebuf;
751  std::stringstream uri;
752  uri << ip << ":" << port;
753 
754  return uri.str();
755 }
756 
757 } // namespace ros
boost::function< void(const TransportTCPPtr &)> AcceptCallback
Definition: transport_tcp.h:84
virtual void parseHeader(const Header &header)
Provides an opportunity for transport-specific options to come in through the header.
bool addEvents(int sock, int events)
Add events to be polled on a socket.
Definition: poll_set.cpp:121
ROSCPP_DECL int set_non_blocking(socket_fd_t &socket)
Definition: io.cpp:237
socket_fd_t sock_
virtual int32_t write(uint8_t *buffer, uint32_t size)
Write a number of bytes from the supplied buffer. Not guaranteed to actually write that number of byt...
bool isOnlyLocalhostAllowed() const
returns true if this transport is only allowed to talk to localhost
Definition: transport.h:147
virtual void disableWrite()
Disable writing on this transport. Allows derived classes to, for example, disable write polling for ...
std::string connected_host_
Callback read_cb_
Definition: transport.h:136
Manages a set of sockets being polled through the poll() function call.
Definition: poll_set.h:57
virtual void enableRead()
Enable reading on this transport. Allows derived classes to, for example, enable read polling for asy...
std::string cached_remote_host_
virtual void enableWrite()
Enable writing on this transport. Allows derived classes to, for example, enable write polling for as...
ROSCPP_DECL const char * last_socket_error_string()
Definition: io.cpp:62
void setNoDelay(bool nodelay)
#define ROSCPP_LOG_DEBUG(...)
Definition: file_log.h:35
AcceptCallback accept_cb_
bool setSocket(int sock)
Set the socket to be used by this transport.
virtual void disableRead()
Disable reading on this transport. Allows derived classes to, for example, disable read polling for a...
static bool s_use_ipv6_
Definition: transport_tcp.h:60
ROSCPP_DECL bool last_socket_error_is_would_block()
Definition: io.cpp:74
#define ROS_ASSERT_MSG(cond,...)
virtual void close()
Close this transport. Once this call has returned, writing on this transport should always return an ...
bool delEvents(int sock, int events)
Delete events to be polled on a socket.
Definition: poll_set.cpp:140
virtual std::string getTransportInfo()
Returns a string description of both the type of transport and who the transport is connected to...
bool initializeSocket()
Initializes the assigned socket – sets it to non-blocking and enables reading.
bool delSocket(int sock)
Delete a socket.
Definition: poll_set.cpp:91
boost::recursive_mutex close_mutex_
#define ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN
Definition: io.h:108
bool getValue(const std::string &key, std::string &value) const
virtual int32_t read(uint8_t *buffer, uint32_t size)
Read a number of bytes into the supplied buffer. Not guaranteed to actually read that number of bytes...
sockaddr_storage server_address_
TransportTCPPtr accept()
Accept a connection on a server socket. Blocks until a connection is available.
sockaddr_storage local_address_
bool listen(int port, int backlog, const AcceptCallback &accept_cb)
Start a server socket and listen on a port.
boost::function< void(const TransportPtr &)> Callback
Definition: transport.h:105
Callback disconnect_cb_
Definition: transport.h:135
static bool s_use_keepalive_
Definition: transport_tcp.h:59
void socketUpdate(int events)
boost::shared_ptr< TransportTCP > TransportTCPPtr
Definition: forwards.h:58
#define ROS_INVALID_SOCKET
Definition: io.h:107
Callback write_cb_
Definition: transport.h:137
#define ROSCPP_CONN_LOG_DEBUG(...)
Definition: file_log.h:36
TransportTCP(PollSet *poll_set, int flags=0)
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:575
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
#define ROS_SOCKETS_SHUT_RDWR
Definition: io.h:106
std::string getClientURI()
Returns the URI of the remote host.
bool connect(const std::string &host, int port)
Connect to a remote host.
ROSCPP_DECL int last_socket_error()
Definition: io.cpp:55
void setKeepAlive(bool use, uint32_t idle, uint32_t interval, uint32_t count)
#define ROS_ASSERT(cond)
ROSCPP_DECL int close_socket(socket_fd_t &socket)
Close the socket.
Definition: io.cpp:258
bool addSocket(int sock, const SocketUpdateFunc &update_func, const TransportPtr &transport=TransportPtr())
Add a socket.
Definition: poll_set.cpp:65
#define ROS_ERROR(...)
#define ROS_DEBUG(...)
virtual ~TransportTCP()


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Wed Dec 20 2017 03:58:41