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