transport_udp.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 
36 #include "ros/poll_set.h"
37 #include "ros/file_log.h"
38 
39 #include <ros/assert.h>
40 #include <boost/bind.hpp>
41 #ifndef _WIN32
42  #include <sys/socket.h> // explicit include required for FreeBSD
43 #endif
44 
45 #include <fcntl.h>
46 #if defined(__APPLE__)
47  // For readv() and writev()
48  #include <sys/types.h>
49  #include <sys/uio.h>
50  #include <unistd.h>
51 #elif defined(__ANDROID__)
52  // For readv() and writev() on ANDROID
53  #include <sys/uio.h>
54 #elif defined(_POSIX_VERSION)
55  // For readv() and writev()
56  #include <sys/uio.h>
57 #endif
58 
59 namespace ros
60 {
61 
62 TransportUDP::TransportUDP(PollSet* poll_set, int flags, int max_datagram_size)
63 : sock_(-1)
64 , closed_(false)
65 , expecting_read_(false)
66 , expecting_write_(false)
67 , is_server_(false)
68 , server_address_{}
70 , server_port_(-1)
71 , local_port_(-1)
72 , poll_set_(poll_set)
73 , flags_(flags)
74 , connection_id_(0)
76 , total_blocks_(0)
77 , last_block_(0)
78 , max_datagram_size_(max_datagram_size)
79 , data_filled_(0)
80 , reorder_buffer_(0)
81 , reorder_bytes_(0)
82 {
83  // This may eventually be machine dependent
84  if (max_datagram_size_ == 0)
85  max_datagram_size_ = 1500;
86  reorder_buffer_ = new uint8_t[max_datagram_size_];
88  data_buffer_ = new uint8_t[max_datagram_size_];
90 }
91 
93 {
94  ROS_ASSERT_MSG(sock_ == ROS_INVALID_SOCKET, "TransportUDP socket [%d] was never closed", sock_);
95  delete [] reorder_buffer_;
96  delete [] data_buffer_;
97 }
98 
100 {
101  sock_ = sock;
102  return initializeSocket();
103 }
104 
106 {
107  {
108  boost::mutex::scoped_lock lock(close_mutex_);
109 
110  if (closed_)
111  {
112  return;
113  }
114  }
115 
116  if((events & POLLERR) ||
117  (events & POLLHUP) ||
118  (events & POLLNVAL))
119  {
120  ROSCPP_LOG_DEBUG("Socket %d closed with (ERR|HUP|NVAL) events %d", sock_, events);
121  close();
122  }
123  else
124  {
125  if ((events & POLLIN) && expecting_read_)
126  {
127  if (read_cb_)
128  {
129  read_cb_(shared_from_this());
130  }
131  }
132 
133  if ((events & POLLOUT) && expecting_write_)
134  {
135  if (write_cb_)
136  {
137  write_cb_(shared_from_this());
138  }
139  }
140  }
141 
142 }
143 
145 {
146  std::stringstream str;
147  str << "UDPROS connection on port " << local_port_ << " to [" << cached_remote_host_ << "]";
148  return str.str();
149 }
150 
151 bool TransportUDP::connect(const std::string& host, int port, int connection_id)
152 {
153  if (!isHostAllowed(host))
154  return false; // adios amigo
155 
156  sock_ = socket(AF_INET, SOCK_DGRAM, 0);
157  connection_id_ = connection_id;
158 
159  if (sock_ == ROS_INVALID_SOCKET)
160  {
161  ROS_ERROR("socket() failed with error [%s]", last_socket_error_string());
162  return false;
163  }
164 
165  sockaddr_in sin = {};
166  sin.sin_family = AF_INET;
167  if (inet_addr(host.c_str()) == INADDR_NONE)
168  {
169  struct addrinfo* addr;
170  struct addrinfo hints;
171  memset(&hints, 0, sizeof(hints));
172  hints.ai_family = AF_UNSPEC;
173 
174  if (getaddrinfo(host.c_str(), NULL, &hints, &addr) != 0)
175  {
176  close();
177  ROS_ERROR("couldn't resolve host [%s]", host.c_str());
178  return false;
179  }
180 
181  bool found = false;
182  struct addrinfo* it = addr;
183  for (; it; it = it->ai_next)
184  {
185  if (it->ai_family == AF_INET)
186  {
187  memcpy(&sin, it->ai_addr, it->ai_addrlen);
188  sin.sin_family = it->ai_family;
189  sin.sin_port = htons(port);
190 
191  found = true;
192  break;
193  }
194  }
195 
196  freeaddrinfo(addr);
197 
198  if (!found)
199  {
200  ROS_ERROR("Couldn't find an AF_INET address for [%s]\n", host.c_str());
201  return false;
202  }
203 
204  ROSCPP_LOG_DEBUG("Resolved host [%s] to [%s]", host.c_str(), inet_ntoa(sin.sin_addr));
205  }
206  else
207  {
208  sin.sin_addr.s_addr = inet_addr(host.c_str()); // already an IP addr
209  }
210 
211  sin.sin_port = htons(port);
212 
213  if (::connect(sock_, (sockaddr *)&sin, sizeof(sin)))
214  {
215  ROSCPP_LOG_DEBUG("Connect to udpros host [%s:%d] failed with error [%s]", host.c_str(), port, last_socket_error_string());
216  close();
217 
218  return false;
219  }
220 
221  // from daniel stonier:
222 #ifdef WIN32
223  // This is hackish, but windows fails at recv() if its slow to connect (e.g. happens with wireless)
224  // recv() needs to check if its connected or not when its asynchronous?
225  Sleep(100);
226 #endif
227 
228  std::stringstream ss;
229  ss << host << ":" << port << " on socket " << sock_;
230  cached_remote_host_ = ss.str();
231 
232  if (!initializeSocket())
233  {
234  return false;
235  }
236 
237  ROSCPP_LOG_DEBUG("Connect succeeded to [%s:%d] on socket [%d]", host.c_str(), port, sock_);
238 
239  return true;
240 }
241 
242 bool TransportUDP::createIncoming(int port, bool is_server)
243 {
244  is_server_ = is_server;
245 
246  sock_ = socket(AF_INET, SOCK_DGRAM, 0);
247 
248  if (sock_ == ROS_INVALID_SOCKET)
249  {
250  ROS_ERROR("socket() failed with error [%s]", last_socket_error_string());
251  return false;
252  }
253 
254  server_address_.sin_family = AF_INET;
255  server_address_.sin_port = htons(port);
256  server_address_.sin_addr.s_addr = isOnlyLocalhostAllowed() ?
257  htonl(INADDR_LOOPBACK) :
258  INADDR_ANY;
259  if (bind(sock_, (sockaddr *)&server_address_, sizeof(server_address_)) < 0)
260  {
261  ROS_ERROR("bind() failed with error [%s]", last_socket_error_string());
262  return false;
263  }
264 
265  socklen_t len = sizeof(server_address_);
266  getsockname(sock_, (sockaddr *)&server_address_, &len);
267  server_port_ = ntohs(server_address_.sin_port);
268  ROSCPP_LOG_DEBUG("UDPROS server listening on port [%d]", server_port_);
269 
270  if (!initializeSocket())
271  {
272  return false;
273  }
274 
275  enableRead();
276 
277  return true;
278 }
279 
281 {
283 
284  if (!(flags_ & SYNCHRONOUS))
285  {
286  int result = set_non_blocking(sock_);
287  if ( result != 0 ) {
288  ROS_ERROR("setting socket [%d] as non_blocking failed with error [%d]", sock_, result);
289  close();
290  return false;
291  }
292  }
293 
294  socklen_t len = sizeof(local_address_);
295  getsockname(sock_, (sockaddr *)&local_address_, &len);
296  local_port_ = ntohs(local_address_.sin_port);
297 
298  ROS_ASSERT(poll_set_ || (flags_ & SYNCHRONOUS));
299  if (poll_set_)
300  {
301  poll_set_->addSocket(sock_, boost::bind(&TransportUDP::socketUpdate, this, _1), shared_from_this());
302  }
303 
304  return true;
305 }
306 
308 {
309  Callback disconnect_cb;
310 
311  if (!closed_)
312  {
313  {
314  boost::mutex::scoped_lock lock(close_mutex_);
315 
316  if (!closed_)
317  {
318  closed_ = true;
319 
320  ROSCPP_LOG_DEBUG("UDP socket [%d] closed", sock_);
321 
323 
324  if (poll_set_)
325  {
327  }
328 
329  if ( close_socket(sock_) != 0 )
330  {
331  ROS_ERROR("Error closing socket [%d]: [%s]", sock_, last_socket_error_string());
332  }
333 
335 
336  disconnect_cb = disconnect_cb_;
337 
339  read_cb_ = Callback();
340  write_cb_ = Callback();
341  }
342  }
343  }
344 
345  if (disconnect_cb)
346  {
347  disconnect_cb(shared_from_this());
348  }
349 }
350 
351 int32_t TransportUDP::read(uint8_t* buffer, uint32_t size)
352 {
353  {
354  boost::mutex::scoped_lock lock(close_mutex_);
355  if (closed_)
356  {
357  ROSCPP_LOG_DEBUG("Tried to read on a closed socket [%d]", sock_);
358  return -1;
359  }
360  }
361 
362  ROS_ASSERT((int32_t)size > 0);
363 
364  uint32_t bytes_read = 0;
365 
366  while (bytes_read < size)
367  {
369 
370  // Get the data either from the reorder buffer or the socket
371  // copy_bytes will contain the read size.
372  // from_previous is true if the data belongs to the previous UDP datagram.
373  uint32_t copy_bytes = 0;
374  bool from_previous = false;
375  if (reorder_bytes_)
376  {
378  {
379  from_previous = true;
380  }
381 
382  copy_bytes = std::min(size - bytes_read, reorder_bytes_);
383  header = reorder_header_;
384  memcpy(buffer + bytes_read, reorder_start_, copy_bytes);
385  reorder_bytes_ -= copy_bytes;
386  reorder_start_ += copy_bytes;
387  }
388  else
389  {
390  if (data_filled_ == 0)
391  {
392 #if defined(WIN32)
393  SSIZE_T num_bytes = 0;
394  DWORD received_bytes = 0;
395  DWORD flags = 0;
396  WSABUF iov[2];
397  iov[0].buf = reinterpret_cast<char*>(&header);
398  iov[0].len = sizeof(header);
399  iov[1].buf = reinterpret_cast<char*>(data_buffer_);
400  iov[1].len = max_datagram_size_ - sizeof(header);
401  int rc = WSARecv(sock_, iov, 2, &received_bytes, &flags, NULL, NULL);
402  if ( rc == SOCKET_ERROR) {
403  num_bytes = -1;
404  } else {
405  num_bytes = received_bytes;
406  }
407 #else
408  ssize_t num_bytes;
409  struct iovec iov[2];
410  iov[0].iov_base = &header;
411  iov[0].iov_len = sizeof(header);
412  iov[1].iov_base = data_buffer_;
413  iov[1].iov_len = max_datagram_size_ - sizeof(header);
414  // Read a datagram with header
415  num_bytes = readv(sock_, iov, 2);
416 #endif
417  if (num_bytes < 0)
418  {
420  {
421  num_bytes = 0;
422  break;
423  }
424  else
425  {
426  ROSCPP_LOG_DEBUG("readv() failed with error [%s]", last_socket_error_string());
427  close();
428  break;
429  }
430  }
431  else if (num_bytes == 0)
432  {
433  ROSCPP_LOG_DEBUG("Socket [%d] received 0/%d bytes, closing", sock_, size);
434  close();
435  return -1;
436  }
437  else if (num_bytes < (unsigned) sizeof(header))
438  {
439  ROS_ERROR("Socket [%d] received short header (%d bytes): %s", sock_, int(num_bytes), last_socket_error_string());
440  close();
441  return -1;
442  }
443 
444  num_bytes -= sizeof(header);
445  data_filled_ = num_bytes;
447  }
448  else
449  {
450  from_previous = true;
451  }
452 
453  copy_bytes = std::min(size - bytes_read, data_filled_);
454  // Copy from the data buffer, whether it has data left in it from a previous datagram or
455  // was just filled by readv()
456  memcpy(buffer + bytes_read, data_start_, copy_bytes);
457  data_filled_ -= copy_bytes;
458  data_start_ += copy_bytes;
459  }
460 
461 
462  if (from_previous)
463  {
464  // We are simply reading data from the last UDP datagram, nothing to
465  // parse
466  bytes_read += copy_bytes;
467  }
468  else
469  {
470  // This datagram is new, process header
471  switch (header.op_)
472  {
473  case ROS_UDP_DATA0:
475  {
476  ROS_DEBUG("Received new message [%d:%d], while still working on [%d] (block %d of %d)", header.message_id_, header.block_, current_message_id_, last_block_ + 1, total_blocks_);
477  reorder_header_ = header;
478 
479  // Copy the entire data buffer to the reorder buffer, as we will
480  // need to replay this UDP datagram in the next call.
485  total_blocks_ = 0;
486  last_block_ = 0;
487 
488  data_filled_ = 0;
490  return -1;
491  }
492  total_blocks_ = header.block_;
493  last_block_ = 0;
495  break;
496  case ROS_UDP_DATAN:
497  if (header.message_id_ != current_message_id_)
498  {
499  ROS_DEBUG("Message Id mismatch: %d != %d", header.message_id_, current_message_id_);
500  data_filled_ = 0; // discard datagram
501  return 0;
502  }
503  if (header.block_ != last_block_ + 1)
504  {
505  ROS_DEBUG("Expected block %d, received %d", last_block_ + 1, header.block_);
506  data_filled_ = 0; // discard datagram
507  return 0;
508  }
509  last_block_ = header.block_;
510 
511  break;
512  default:
513  ROS_ERROR("Unexpected UDP header OP [%d]", header.op_);
514  return -1;
515  }
516 
517  bytes_read += copy_bytes;
518 
519  if (last_block_ == (total_blocks_ - 1))
520  {
522  break;
523  }
524  }
525  }
526 
527  return bytes_read;
528 }
529 
530 int32_t TransportUDP::write(uint8_t* buffer, uint32_t size)
531 {
532  {
533  boost::mutex::scoped_lock lock(close_mutex_);
534 
535  if (closed_)
536  {
537  ROSCPP_LOG_DEBUG("Tried to write on a closed socket [%d]", sock_);
538  return -1;
539  }
540  }
541 
542  ROS_ASSERT((int32_t)size > 0);
543 
544  const uint32_t max_payload_size = max_datagram_size_ - sizeof(TransportUDPHeader);
545 
546  uint32_t bytes_sent = 0;
547  uint32_t this_block = 0;
548  if (++current_message_id_ == 0)
550  while (bytes_sent < size)
551  {
555  if (this_block == 0)
556  {
557  header.op_ = ROS_UDP_DATA0;
558  header.block_ = (size + max_payload_size - 1) / max_payload_size;
559  }
560  else
561  {
562  header.op_ = ROS_UDP_DATAN;
563  header.block_ = this_block;
564  }
565  ++this_block;
566 #if defined(WIN32)
567  WSABUF iov[2];
568  DWORD sent_bytes;
569  SSIZE_T num_bytes = 0;
570  DWORD flags = 0;
571  int rc;
572  iov[0].buf = reinterpret_cast<char*>(&header);
573  iov[0].len = sizeof(header);
574  iov[1].buf = reinterpret_cast<char*>(buffer + bytes_sent);
575  iov[1].len = std::min(max_payload_size, size - bytes_sent);
576  rc = WSASend(sock_, iov, 2, &sent_bytes, flags, NULL, NULL);
577  num_bytes = sent_bytes;
578  if (rc == SOCKET_ERROR) {
579  num_bytes = -1;
580  }
581 #else
582  struct iovec iov[2];
583  iov[0].iov_base = &header;
584  iov[0].iov_len = sizeof(header);
585  iov[1].iov_base = buffer + bytes_sent;
586  iov[1].iov_len = std::min(max_payload_size, size - bytes_sent);
587  ssize_t num_bytes = writev(sock_, iov, 2);
588 #endif
589  //usleep(100);
590  if (num_bytes < 0)
591  {
592  if( !last_socket_error_is_would_block() ) // Actually EAGAIN or EWOULDBLOCK on posix
593  {
594  ROSCPP_LOG_DEBUG("writev() failed with error [%s]", last_socket_error_string());
595  close();
596  break;
597  }
598  else
599  {
600  num_bytes = 0;
601  --this_block;
602  }
603  }
604  else if (num_bytes < (unsigned) sizeof(header))
605  {
606  ROSCPP_LOG_DEBUG("Socket [%d] short write (%d bytes), closing", sock_, int(num_bytes));
607  close();
608  break;
609  }
610  else
611  {
612  num_bytes -= sizeof(header);
613  }
614  bytes_sent += num_bytes;
615  }
616 
617  return bytes_sent;
618 }
619 
621 {
622  {
623  boost::mutex::scoped_lock lock(close_mutex_);
624 
625  if (closed_)
626  {
627  return;
628  }
629  }
630 
631  if (!expecting_read_)
632  {
633  poll_set_->addEvents(sock_, POLLIN);
634  expecting_read_ = true;
635  }
636 }
637 
639 {
641 
642  {
643  boost::mutex::scoped_lock lock(close_mutex_);
644 
645  if (closed_)
646  {
647  return;
648  }
649  }
650 
651  if (expecting_read_)
652  {
653  poll_set_->delEvents(sock_, POLLIN);
654  expecting_read_ = false;
655  }
656 }
657 
659 {
660  {
661  boost::mutex::scoped_lock lock(close_mutex_);
662 
663  if (closed_)
664  {
665  return;
666  }
667  }
668 
669  if (!expecting_write_)
670  {
671  poll_set_->addEvents(sock_, POLLOUT);
672  expecting_write_ = true;
673  }
674 }
675 
677 {
678  {
679  boost::mutex::scoped_lock lock(close_mutex_);
680 
681  if (closed_)
682  {
683  return;
684  }
685  }
686 
687  if (expecting_write_)
688  {
689  poll_set_->delEvents(sock_, POLLOUT);
690  expecting_write_ = false;
691  }
692 }
693 
694 TransportUDPPtr TransportUDP::createOutgoing(std::string host, int port, int connection_id, int max_datagram_size)
695 {
697 
698  TransportUDPPtr transport(boost::make_shared<TransportUDP>(poll_set_, flags_, max_datagram_size));
699  if (!transport->connect(host, port, connection_id))
700  {
701  ROS_ERROR("Failed to create outgoing connection");
702  return TransportUDPPtr();
703  }
704  return transport;
705 
706 }
707 
709 {
711 
712  sockaddr_storage sas;
713  socklen_t sas_len = sizeof(sas);
714  getpeername(sock_, (sockaddr *)&sas, &sas_len);
715 
716  sockaddr_in *sin = (sockaddr_in *)&sas;
717 
718  char namebuf[128] = {};
719  int port = ntohs(sin->sin_port);
720  strncpy(namebuf, inet_ntoa(sin->sin_addr), sizeof(namebuf)-1);
721 
722  std::string ip = namebuf;
723  std::stringstream uri;
724  uri << ip << ":" << port;
725 
726  return uri.str();
727 }
728 
729 }
boost::mutex close_mutex_
std::string getClientURI()
Returns the URI of the remote host.
TransportUDPPtr createOutgoing(std::string host, int port, int conn_id, int max_datagram_size)
Create a connection to a server socket.
socket_fd_t sock_
bool connect(const std::string &host, int port, int conn_id)
Connect to a remote host.
bool addEvents(int sock, int events)
Add events to be polled on a socket.
Definition: poll_set.cpp:126
ROSCPP_DECL int set_non_blocking(socket_fd_t &socket)
Definition: io.cpp:371
TransportUDP(PollSet *poll_set, int flags=0, int max_datagram_size=0)
bool createIncoming(int port, bool is_server)
Start a server socket and listen on a port.
virtual void enableWrite()
Enable writing on this transport. Allows derived classes to, for example, enable write polling for as...
bool initializeSocket()
Initializes the assigned socket – sets it to non-blocking and enables reading.
#define ROS_UDP_DATA0
Definition: transport_udp.h:53
Callback read_cb_
Definition: transport.h:137
virtual void disableRead()
Disable reading on this transport. Allows derived classes to, for example, disable read polling for a...
Manages a set of sockets being polled through the poll() function call.
Definition: poll_set.h:57
void socketUpdate(int events)
sockaddr_in local_address_
uint8_t * data_buffer_
uint16_t total_blocks_
uint8_t * reorder_buffer_
ROSCPP_DECL const char * last_socket_error_string()
Definition: io.cpp:74
boost::shared_ptr< TransportUDP > TransportUDPPtr
Definition: forwards.h:60
virtual std::string getTransportInfo()
Returns a string description of both the type of transport and who the transport is connected to...
std::string cached_remote_host_
virtual void disableWrite()
Disable writing on this transport. Allows derived classes to, for example, disable write polling for ...
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 setSocket(int sock)
Set the socket to be used by this transport.
#define ROSCPP_LOG_DEBUG(...)
Definition: file_log.h:35
uint8_t current_message_id_
ROSCPP_DECL bool last_socket_error_is_would_block()
Definition: io.cpp:86
#define ROS_ASSERT_MSG(cond,...)
struct ros::TransportUDPHeader TransportUDPHeader
TransportUDPHeader reorder_header_
bool delEvents(int sock, int events)
Delete events to be polled on a socket.
Definition: poll_set.cpp:148
bool delSocket(int sock)
Delete a socket.
Definition: poll_set.cpp:94
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...
virtual void enableRead()
Enable reading on this transport. Allows derived classes to, for example, enable read polling for asy...
sockaddr_in server_address_
#define ROS_UDP_DATAN
Definition: transport_udp.h:54
boost::function< void(const TransportPtr &)> Callback
Definition: transport.h:106
Callback disconnect_cb_
Definition: transport.h:136
virtual ~TransportUDP()
uint32_t max_datagram_size_
virtual void close()
Close this transport. Once this call has returned, writing on this transport should always return an ...
#define ROS_INVALID_SOCKET
Definition: io.h:107
Callback write_cb_
Definition: transport.h:138
uint32_t reorder_bytes_
uint8_t * data_start_
const std::string header
uint32_t connection_id_
#define ROS_ASSERT(cond)
ROSCPP_DECL int close_socket(socket_fd_t &socket)
Close the socket.
Definition: io.cpp:392
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:111
bool isOnlyLocalhostAllowed() const
returns true if this transport is only allowed to talk to localhost
Definition: transport.h:148
bool addSocket(int sock, const SocketUpdateFunc &update_func, const TransportPtr &transport=TransportPtr())
Add a socket.
Definition: poll_set.cpp:66
#define ROS_ERROR(...)
uint8_t * reorder_start_
#define ROS_DEBUG(...)


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27