PageRenderTime 60ms CodeModel.GetById 25ms RepoModel.GetById 1ms app.codeStats 0ms

/clients/rospy/src/rospy/impl/tcpros_base.py

https://gitlab.com/F34140r/ros_comm
Python | 785 lines | 684 code | 21 blank | 80 comment | 27 complexity | 93fb9a01968a116c804bdd1fb5d0a911 MD5 | raw file
Possible License(s): LGPL-2.1
  1. # Software License Agreement (BSD License)
  2. #
  3. # Copyright (c) 2008, Willow Garage, Inc.
  4. # All rights reserved.
  5. #
  6. # Redistribution and use in source and binary forms, with or without
  7. # modification, are permitted provided that the following conditions
  8. # are met:
  9. #
  10. # * Redistributions of source code must retain the above copyright
  11. # notice, this list of conditions and the following disclaimer.
  12. # * Redistributions in binary form must reproduce the above
  13. # copyright notice, this list of conditions and the following
  14. # disclaimer in the documentation and/or other materials provided
  15. # with the distribution.
  16. # * Neither the name of Willow Garage, Inc. nor the names of its
  17. # contributors may be used to endorse or promote products derived
  18. # from this software without specific prior written permission.
  19. #
  20. # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  21. # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  22. # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  23. # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  24. # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  25. # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  26. # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  27. # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  28. # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  29. # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  30. # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  31. # POSSIBILITY OF SUCH DAMAGE.
  32. #
  33. # Revision $Id$
  34. """Internal use: common TCPROS libraries"""
  35. try:
  36. from cStringIO import StringIO #Python 2.x
  37. python3 = 0
  38. except ImportError:
  39. from io import StringIO, BytesIO #Python 3.x
  40. python3 = 1
  41. import socket
  42. import logging
  43. try:
  44. import _thread
  45. except ImportError:
  46. import thread as _thread
  47. import threading
  48. import time
  49. import traceback
  50. import select
  51. import rosgraph
  52. import rosgraph.network
  53. from genpy import DeserializationError, Message
  54. from rosgraph.network import read_ros_handshake_header, write_ros_handshake_header
  55. # TODO: remove * import from core
  56. from rospy.core import *
  57. from rospy.core import logwarn, loginfo, logerr, logdebug, rospydebug, rospyerr, rospywarn
  58. from rospy.exceptions import ROSInternalException, TransportException, TransportTerminated, TransportInitError
  59. from rospy.msg import deserialize_messages, serialize_message
  60. from rospy.service import ServiceException
  61. from rospy.impl.transport import Transport, BIDIRECTIONAL
  62. logger = logging.getLogger('rospy.tcpros')
  63. # Receive buffer size for topics/services (in bytes)
  64. DEFAULT_BUFF_SIZE = 65536
  65. ## name of our customized TCP protocol for accepting flows over server socket
  66. TCPROS = "TCPROS"
  67. _PARAM_TCP_KEEPALIVE = '/tcp_keepalive'
  68. _use_tcp_keepalive = None
  69. _use_tcp_keepalive_lock = threading.Lock()
  70. def _is_use_tcp_keepalive():
  71. global _use_tcp_keepalive
  72. if _use_tcp_keepalive is not None:
  73. return _use_tcp_keepalive
  74. with _use_tcp_keepalive_lock:
  75. if _use_tcp_keepalive is not None:
  76. return _use_tcp_keepalive
  77. # in order to prevent circular dependencies, this does not use the
  78. # builtin libraries for interacting with the parameter server
  79. m = rospy.core.xmlrpcapi(rosgraph.get_master_uri())
  80. code, msg, val = m.getParam(rospy.names.get_caller_id(), _PARAM_TCP_KEEPALIVE)
  81. _use_tcp_keepalive = val if code == 1 else True
  82. return _use_tcp_keepalive
  83. def recv_buff(sock, b, buff_size):
  84. """
  85. Read data from socket into buffer.
  86. @param sock: socket to read from
  87. @type sock: socket.socket
  88. @param b: buffer to receive into
  89. @type b: StringIO
  90. @param buff_size: recv read size
  91. @type buff_size: int
  92. @return: number of bytes read
  93. @rtype: int
  94. """
  95. d = sock.recv(buff_size)
  96. if d:
  97. b.write(d)
  98. return len(d)
  99. else: #bomb out
  100. raise TransportTerminated("unable to receive data from sender, check sender's logs for details")
  101. class TCPServer(object):
  102. """
  103. Simple server that accepts inbound TCP/IP connections and hands
  104. them off to a handler function. TCPServer obeys the
  105. ROS_IP/ROS_HOSTNAME environment variables
  106. """
  107. def __init__(self, inbound_handler, port=0):
  108. """
  109. Setup a server socket listening on the specified port. If the
  110. port is omitted, will choose any open port.
  111. @param inbound_handler: handler to invoke with
  112. new connection
  113. @type inbound_handler: fn(sock, addr)
  114. @param port: port to bind to, omit/0 to bind to any
  115. @type port: int
  116. """
  117. self.port = port #will get overwritten if port=0
  118. self.addr = None #set at socket bind
  119. self.is_shutdown = False
  120. self.inbound_handler = inbound_handler
  121. try:
  122. self.server_sock = self._create_server_sock()
  123. except:
  124. self.server_sock = None
  125. raise
  126. def start(self):
  127. """Runs the run() loop in a separate thread"""
  128. _thread.start_new_thread(self.run, ())
  129. def run(self):
  130. """
  131. Main TCP receive loop. Should be run in a separate thread -- use start()
  132. to do this automatically.
  133. """
  134. self.is_shutdown = False
  135. if not self.server_sock:
  136. raise ROSInternalException("%s did not connect"%self.__class__.__name__)
  137. while not self.is_shutdown:
  138. try:
  139. (client_sock, client_addr) = self.server_sock.accept()
  140. except socket.timeout:
  141. continue
  142. except IOError as e:
  143. (errno, msg) = e.args
  144. if errno == 4: #interrupted system call
  145. continue
  146. raise
  147. if self.is_shutdown:
  148. break
  149. try:
  150. #leave threading decisions up to inbound_handler
  151. self.inbound_handler(client_sock, client_addr)
  152. except socket.error as e:
  153. if not self.is_shutdown:
  154. traceback.print_exc()
  155. logwarn("Failed to handle inbound connection due to socket error: %s"%e)
  156. logdebug("TCPServer[%s] shutting down", self.port)
  157. def get_full_addr(self):
  158. """
  159. @return: (ip address, port) of server socket binding
  160. @rtype: (str, int)
  161. """
  162. # return rosgraph.network.get_host_name() instead of address so that it
  163. # obeys ROS_IP/ROS_HOSTNAME behavior
  164. return (rosgraph.network.get_host_name(), self.port)
  165. def _create_server_sock(self):
  166. """
  167. binds the server socket. ROS_IP/ROS_HOSTNAME may restrict
  168. binding to loopback interface.
  169. """
  170. if rosgraph.network.use_ipv6():
  171. server_sock = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
  172. else:
  173. server_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  174. server_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  175. logdebug('binding to ' + str(rosgraph.network.get_bind_address()) + ' ' + str(self.port))
  176. server_sock.bind((rosgraph.network.get_bind_address(), self.port))
  177. (self.addr, self.port) = server_sock.getsockname()[0:2]
  178. logdebug('bound to ' + str(self.addr) + ' ' + str(self.port))
  179. server_sock.listen(5)
  180. return server_sock
  181. def shutdown(self):
  182. """shutdown I/O resources uses by this server"""
  183. if not self.is_shutdown:
  184. self.is_shutdown = True
  185. self.server_sock.close()
  186. # base maintains a tcpros_server singleton that is shared between
  187. # services and topics for inbound connections. This global is set in
  188. # the tcprosserver constructor. Constructor is called by init_tcpros()
  189. _tcpros_server = None
  190. def init_tcpros_server(port=0):
  191. """
  192. starts the TCPROS server socket for inbound connections
  193. @param port: listen on the provided port. If the port number is 0, the port will
  194. be chosen randomly
  195. @type port: int
  196. """
  197. global _tcpros_server
  198. if _tcpros_server is None:
  199. _tcpros_server = TCPROSServer(port=port)
  200. rospy.core.add_shutdown_hook(_tcpros_server.shutdown)
  201. return _tcpros_server
  202. def start_tcpros_server():
  203. """
  204. start the TCPROS server if it has not started already
  205. """
  206. if _tcpros_server is None:
  207. init_tcpros_server()
  208. return _tcpros_server.start_server()
  209. # provide an accessor of this so that the TCPROS Server is entirely hidden from upper layers
  210. def get_tcpros_server_address():
  211. """
  212. get the address of the tcpros server.
  213. @raise Exception: if tcpros server has not been started or created
  214. """
  215. return _tcpros_server.get_address()
  216. def _error_connection_handler(sock, client_addr, header):
  217. """
  218. utility handler that does nothing more than provide a rejection header
  219. @param sock: socket connection
  220. @type sock: socket.socket
  221. @param client_addr: client address
  222. @type client_addr: str
  223. @param header: request header
  224. @type header: dict
  225. """
  226. return {'error': "unhandled connection"}
  227. class TCPROSServer(object):
  228. """
  229. ROS Protocol handler for TCPROS. Accepts both TCPROS topic
  230. connections as well as ROS service connections over TCP. TCP server
  231. socket is run once start_server() is called -- this is implicitly
  232. called during init_publisher().
  233. """
  234. def __init__(self, port=0):
  235. """
  236. Constructur
  237. @param port: port number to bind to (default 0/any)
  238. @type port: int
  239. """
  240. self.port = port
  241. self.tcp_ros_server = None #: server for receiving tcp conn
  242. self.lock = threading.Lock()
  243. # should be set to fn(sock, client_addr, header) for topic connections
  244. self.topic_connection_handler = _error_connection_handler
  245. # should be set to fn(sock, client_addr, header) for service connections
  246. self.service_connection_handler = _error_connection_handler
  247. def start_server(self):
  248. """
  249. Starts the TCP socket server if one is not already running
  250. """
  251. if self.tcp_ros_server:
  252. return
  253. with self.lock:
  254. try:
  255. if not self.tcp_ros_server:
  256. self.tcp_ros_server = TCPServer(self._tcp_server_callback, self.port)
  257. self.tcp_ros_server.start()
  258. except Exception as e:
  259. self.tcp_ros_server = None
  260. logerr("unable to start TCPROS server: %s\n%s"%(e, traceback.format_exc()))
  261. return 0, "unable to establish TCPROS server: %s"%e, []
  262. def get_address(self):
  263. """
  264. @return: address and port of TCP server socket for accepting
  265. inbound connections
  266. @rtype: str, int
  267. """
  268. if self.tcp_ros_server is not None:
  269. return self.tcp_ros_server.get_full_addr()
  270. return None, None
  271. def shutdown(self, reason=''):
  272. """stops the TCP/IP server responsible for receiving inbound connections"""
  273. if self.tcp_ros_server:
  274. self.tcp_ros_server.shutdown()
  275. def _tcp_server_callback(self, sock, client_addr):
  276. """
  277. TCPServer callback: detects incoming topic or service connection and passes connection accordingly
  278. @param sock: socket connection
  279. @type sock: socket.socket
  280. @param client_addr: client address
  281. @type client_addr: (str, int)
  282. @raise TransportInitError: If transport cannot be succesfully initialized
  283. """
  284. #TODOXXX:rewrite this logic so it is possible to create TCPROSTransport object first, set its protocol,
  285. #and then use that to do the writing
  286. try:
  287. buff_size = 4096 # size of read buffer
  288. if python3 == 0:
  289. #initialize read_ros_handshake_header with BytesIO for Python 3 (instead of bytesarray())
  290. header = read_ros_handshake_header(sock, StringIO(), buff_size)
  291. else:
  292. header = read_ros_handshake_header(sock, BytesIO(), buff_size)
  293. if 'topic' in header:
  294. err_msg = self.topic_connection_handler(sock, client_addr, header)
  295. elif 'service' in header:
  296. err_msg = self.service_connection_handler(sock, client_addr, header)
  297. else:
  298. err_msg = 'no topic or service name detected'
  299. if err_msg:
  300. # shutdown race condition: nodes that come up and down
  301. # quickly can receive connections during teardown.
  302. # We use is_shutdown_requested() because we can get
  303. # into bad connection states during client shutdown
  304. # hooks.
  305. if not rospy.core.is_shutdown_requested():
  306. write_ros_handshake_header(sock, {'error' : err_msg})
  307. raise TransportInitError("Could not process inbound connection: "+err_msg+str(header))
  308. else:
  309. write_ros_handshake_header(sock, {'error' : 'node shutting down'})
  310. return
  311. except rospy.exceptions.TransportInitError as e:
  312. logwarn(str(e))
  313. if sock is not None:
  314. sock.close()
  315. except Exception as e:
  316. # collect stack trace separately in local log file
  317. if not rospy.core.is_shutdown_requested():
  318. logwarn("Inbound TCP/IP connection failed: %s", e)
  319. rospyerr("Inbound TCP/IP connection failed:\n%s", traceback.format_exc(e))
  320. if sock is not None:
  321. sock.close()
  322. class TCPROSTransportProtocol(object):
  323. """
  324. Abstraction of TCPROS connections. Implementations Services/Publishers/Subscribers must implement this
  325. protocol, which defines how messages are deserialized from an inbound connection (read_messages()) as
  326. well as which fields to send when creating a new connection (get_header_fields()).
  327. """
  328. def __init__(self, resolved_name, recv_data_class, queue_size=None, buff_size=DEFAULT_BUFF_SIZE):
  329. """
  330. ctor
  331. @param resolved_name: resolved service or topic name
  332. @type resolved_name: str
  333. @param recv_data_class: message class for deserializing inbound messages
  334. @type recv_data_class: Class
  335. @param queue_size: maximum number of inbound messages to maintain
  336. @type queue_size: int
  337. @param buff_size: receive buffer size (in bytes) for reading from the connection.
  338. @type buff_size: int
  339. """
  340. if recv_data_class and not issubclass(recv_data_class, Message):
  341. raise TransportInitError("Unable to initialize transport: data class is not a message data class")
  342. self.resolved_name = resolved_name
  343. self.recv_data_class = recv_data_class
  344. self.queue_size = queue_size
  345. self.buff_size = buff_size
  346. self.direction = BIDIRECTIONAL
  347. def read_messages(self, b, msg_queue, sock):
  348. """
  349. @param b StringIO: read buffer
  350. @param msg_queue [Message]: queue of deserialized messages
  351. @type msg_queue: [Message]
  352. @param sock socket: protocol can optionally read more data from
  353. the socket, but in most cases the required data will already be
  354. in b
  355. """
  356. # default implementation
  357. deserialize_messages(b, msg_queue, self.recv_data_class, queue_size=self.queue_size)
  358. def get_header_fields(self):
  359. """
  360. Header fields that should be sent over the connection. The header fields
  361. are protocol specific (i.e. service vs. topic, publisher vs. subscriber).
  362. @return: {str : str}: header fields to send over connection
  363. @rtype: dict
  364. """
  365. return {}
  366. # TODO: this still isn't as clean and seamless as I want it to
  367. # be. This code came from the merger of publisher, subscriber, and
  368. # service code into a common TCPROS transport class. The transport is
  369. # customized by a 'protocol' class, which is how the different
  370. # pub/sub/service behaviors are achieved. More behavior needs to be
  371. # transferred from the transport class into the protocol class,
  372. # e.g. deserialization as the state each maintains is somewhat
  373. # duplicative. I would also come up with a better name than
  374. # protocol.
  375. class TCPROSTransport(Transport):
  376. """
  377. Generic implementation of TCPROS exchange routines for both topics and services
  378. """
  379. transport_type = 'TCPROS'
  380. def __init__(self, protocol, name, header=None):
  381. """
  382. ctor
  383. @param name str: identifier
  384. @param protocol TCPROSTransportProtocol protocol implementation
  385. @param header dict: (optional) handshake header if transport handshake header was
  386. already read off of transport.
  387. @raise TransportInitError if transport cannot be initialized according to arguments
  388. """
  389. super(TCPROSTransport, self).__init__(protocol.direction, name=name)
  390. if not name:
  391. raise TransportInitError("Unable to initialize transport: name is not set")
  392. self.protocol = protocol
  393. self.socket = None
  394. self.endpoint_id = 'unknown'
  395. self.dest_address = None # for reconnection
  396. if python3 == 0: # Python 2.x
  397. self.read_buff = StringIO()
  398. self.write_buff = StringIO()
  399. else: # Python 3.x
  400. self.read_buff = BytesIO()
  401. self.write_buff = BytesIO()
  402. #self.write_buff = StringIO()
  403. self.header = header
  404. # #1852 have to hold onto latched messages on subscriber side
  405. self.is_latched = False
  406. self.latch = None
  407. # save the fileno separately so we can garbage collect the
  408. # socket but still unregister will poll objects
  409. self._fileno = None
  410. # these fields are actually set by the remote
  411. # publisher/service. they are set for tools that connect
  412. # without knowing the actual field name
  413. self.md5sum = None
  414. self.type = None
  415. def fileno(self):
  416. """
  417. Get descriptor for select
  418. """
  419. return self._fileno
  420. def set_endpoint_id(self, endpoint_id):
  421. """
  422. Set the endpoint_id of this transport.
  423. Allows the endpoint_id to be set before the socket is initialized.
  424. """
  425. self.endpoint_id = endpoint_id
  426. def set_socket(self, sock, endpoint_id):
  427. """
  428. Set the socket for this transport
  429. @param sock: socket
  430. @type sock: socket.socket
  431. @param endpoint_id: identifier for connection endpoint
  432. @type endpoint_id: str
  433. @raise TransportInitError: if socket has already been set
  434. """
  435. if self.socket is not None:
  436. raise TransportInitError("socket already initialized")
  437. self.socket = sock
  438. self.endpoint_id = endpoint_id
  439. self._fileno = sock.fileno()
  440. def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
  441. """
  442. Establish TCP connection to the specified
  443. address/port. connect() always calls L{write_header()} and
  444. L{read_header()} after the connection is made
  445. @param dest_addr: destination IP address
  446. @type dest_addr: str
  447. @param dest_port: destination port
  448. @type dest_port: int
  449. @param endpoint_id: string identifier for connection (for statistics)
  450. @type endpoint_id: str
  451. @param timeout: (optional keyword) timeout in seconds
  452. @type timeout: float
  453. @raise TransportInitError: if unable to create connection
  454. """
  455. try:
  456. self.endpoint_id = endpoint_id
  457. self.dest_address = (dest_addr, dest_port)
  458. if rosgraph.network.use_ipv6():
  459. s = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
  460. else:
  461. s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  462. if _is_use_tcp_keepalive():
  463. # OSX (among others) does not define these options
  464. if hasattr(socket, 'TCP_KEEPCNT') and \
  465. hasattr(socket, 'TCP_KEEPIDLE') and \
  466. hasattr(socket, 'TCP_KEEPINTVL'):
  467. # turn on KEEPALIVE
  468. s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
  469. # - # keepalive failures before actual connection failure
  470. s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
  471. # - timeout before starting KEEPALIVE process
  472. s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
  473. # - interval to send KEEPALIVE after IDLE timeout
  474. s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
  475. if timeout is not None:
  476. s.settimeout(timeout)
  477. self.socket = s
  478. logdebug('connecting to ' + str(dest_addr)+ ' ' + str(dest_port))
  479. self.socket.connect((dest_addr, dest_port))
  480. self.write_header()
  481. self.read_header()
  482. except TransportInitError as tie:
  483. rospyerr("Unable to initiate TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))
  484. raise
  485. except Exception as e:
  486. #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
  487. rospywarn("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))
  488. # FATAL: no reconnection as error is unknown
  489. self.close()
  490. raise TransportInitError(str(e)) #re-raise i/o error
  491. def _validate_header(self, header):
  492. """
  493. Validate header and initialize fields accordingly
  494. @param header: header fields from publisher
  495. @type header: dict
  496. @raise TransportInitError: if header fails to validate
  497. """
  498. self.header = header
  499. if 'error' in header:
  500. raise TransportInitError("remote error reported: %s"%header['error'])
  501. for required in ['md5sum', 'type']:
  502. if not required in header:
  503. raise TransportInitError("header missing required field [%s]"%required)
  504. self.md5sum = header['md5sum']
  505. self.type = header['type']
  506. if header.get('latching', '0') == '1':
  507. self.is_latched = True
  508. def write_header(self):
  509. """Writes the TCPROS header to the active connection."""
  510. # socket may still be getting spun up, so wait for it to be writable
  511. sock = self.socket
  512. protocol = self.protocol
  513. # race condition on close, better fix is to pass these in,
  514. # functional style, but right now trying to cause minimal
  515. # perturbance to codebase.
  516. if sock is None or protocol is None:
  517. return
  518. fileno = sock.fileno()
  519. ready = None
  520. while not ready:
  521. _, ready, _ = select.select([], [fileno], [])
  522. logger.debug("[%s]: writing header", self.name)
  523. sock.setblocking(1)
  524. self.stat_bytes += write_ros_handshake_header(sock, protocol.get_header_fields())
  525. def read_header(self):
  526. """
  527. Read TCPROS header from active socket
  528. @raise TransportInitError if header fails to validate
  529. """
  530. sock = self.socket
  531. if sock is None:
  532. return
  533. sock.setblocking(1)
  534. self._validate_header(read_ros_handshake_header(sock, self.read_buff, self.protocol.buff_size))
  535. def send_message(self, msg, seq):
  536. """
  537. Convenience routine for services to send a message across a
  538. particular connection. NOTE: write_data is much more efficient
  539. if same message is being sent to multiple connections. Not
  540. threadsafe.
  541. @param msg: message to send
  542. @type msg: Msg
  543. @param seq: sequence number for message
  544. @type seq: int
  545. @raise TransportException: if error occurred sending message
  546. """
  547. # this will call write_data(), so no need to keep track of stats
  548. serialize_message(self.write_buff, seq, msg)
  549. self.write_data(self.write_buff.getvalue())
  550. self.write_buff.truncate(0)
  551. def write_data(self, data):
  552. """
  553. Write raw data to transport
  554. @raise TransportInitialiationError: could not be initialized
  555. @raise TransportTerminated: no longer open for publishing
  556. """
  557. if not self.socket:
  558. raise TransportInitError("TCPROS transport was not successfully initialized")
  559. if self.done:
  560. raise TransportTerminated("connection closed")
  561. try:
  562. #TODO: get rid of sendalls and replace with async-style publishing
  563. self.socket.sendall(data)
  564. self.stat_bytes += len(data)
  565. self.stat_num_msg += 1
  566. except IOError as ioe:
  567. #for now, just document common errno's in code
  568. (errno, msg) = ioe.args
  569. if errno == 32: #broken pipe
  570. logdebug("ERROR: Broken Pipe")
  571. self.close()
  572. raise TransportTerminated(str(errno)+msg)
  573. raise #re-raise
  574. except socket.error as se:
  575. #for now, just document common errno's in code
  576. (errno, msg) = se.args
  577. if errno == 32: #broken pipe
  578. logdebug("[%s]: Closing connection [%s] due to broken pipe", self.name, self.endpoint_id)
  579. self.close()
  580. raise TransportTerminated(msg)
  581. elif errno == 104: #connection reset by peer
  582. logdebug("[%s]: Peer [%s] has closed connection", self.name, self.endpoint_id)
  583. self.close()
  584. raise TransportTerminated(msg)
  585. else:
  586. rospydebug("unknown socket error writing data: %s",traceback.format_exc())
  587. logdebug("[%s]: closing connection [%s] due to unknown socket error: %s", self.name, self.endpoint_id, msg)
  588. self.close()
  589. raise TransportTerminated(str(errno)+' '+msg)
  590. return True
  591. def receive_once(self):
  592. """
  593. block until messages are read off of socket
  594. @return: list of newly received messages
  595. @rtype: [Msg]
  596. @raise TransportException: if unable to receive message due to error
  597. """
  598. sock = self.socket
  599. if sock is None:
  600. raise TransportException("connection not initialized")
  601. b = self.read_buff
  602. msg_queue = []
  603. p = self.protocol
  604. try:
  605. sock.setblocking(1)
  606. while not msg_queue and not self.done and not is_shutdown():
  607. if b.tell() >= 4:
  608. p.read_messages(b, msg_queue, sock)
  609. if not msg_queue:
  610. recv_buff(sock, b, p.buff_size)
  611. self.stat_num_msg += len(msg_queue) #STATS
  612. # set the _connection_header field
  613. for m in msg_queue:
  614. m._connection_header = self.header
  615. # #1852: keep track of last latched message
  616. if self.is_latched and msg_queue:
  617. self.latch = msg_queue[-1]
  618. return msg_queue
  619. except DeserializationError as e:
  620. rospyerr(traceback.format_exc())
  621. raise TransportException("receive_once[%s]: DeserializationError %s"%(self.name, str(e)))
  622. except TransportTerminated as e:
  623. raise #reraise
  624. except ServiceException as e:
  625. raise
  626. except Exception as e:
  627. rospyerr(traceback.format_exc())
  628. raise TransportException("receive_once[%s]: unexpected error %s"%(self.name, str(e)))
  629. return retval
  630. def _reconnect(self):
  631. # This reconnection logic is very hacky right now. I need to
  632. # rewrite the I/O core so that this is handled more centrally.
  633. if self.dest_address is None:
  634. raise ROSInitException("internal error with reconnection state: address not stored")
  635. interval = 0.5 # seconds
  636. while self.socket is None and not self.done and not rospy.is_shutdown():
  637. try:
  638. # set a timeout so that we can continue polling for
  639. # exit. 30. is a bit high, but I'm concerned about
  640. # embedded platforms. To do this properly, we'd have
  641. # to move to non-blocking routines.
  642. self.connect(self.dest_address[0], self.dest_address[1], self.endpoint_id, timeout=30.)
  643. except TransportInitError:
  644. self.socket = None
  645. if self.socket is None:
  646. # exponential backoff
  647. interval = interval * 2
  648. time.sleep(interval)
  649. def receive_loop(self, msgs_callback):
  650. """
  651. Receive messages until shutdown
  652. @param msgs_callback: callback to invoke for new messages received
  653. @type msgs_callback: fn([msg])
  654. """
  655. # - use assert here as this would be an internal error, aka bug
  656. logger.debug("receive_loop for [%s]", self.name)
  657. try:
  658. while not self.done and not is_shutdown():
  659. try:
  660. if self.socket is not None:
  661. msgs = self.receive_once()
  662. if not self.done and not is_shutdown():
  663. msgs_callback(msgs)
  664. else:
  665. self._reconnect()
  666. except TransportException as e:
  667. # set socket to None so we reconnect
  668. try:
  669. if self.socket is not None:
  670. try:
  671. self.socket.shutdown()
  672. except:
  673. pass
  674. finally:
  675. self.socket.close()
  676. except:
  677. pass
  678. self.socket = None
  679. except DeserializationError as e:
  680. #TODO: how should we handle reconnect in this case?
  681. logerr("[%s] error deserializing incoming request: %s"%self.name, str(e))
  682. rospyerr("[%s] error deserializing incoming request: %s"%self.name, traceback.format_exc())
  683. except:
  684. # in many cases this will be a normal hangup, but log internally
  685. try:
  686. #1467 sometimes we get exceptions due to
  687. #interpreter shutdown, so blanket ignore those if
  688. #the reporting fails
  689. rospydebug("exception in receive loop for [%s], may be normal. Exception is %s",self.name, traceback.format_exc())
  690. except: pass
  691. rospydebug("receive_loop[%s]: done condition met, exited loop"%self.name)
  692. finally:
  693. if not self.done:
  694. self.close()
  695. def close(self):
  696. """close i/o and release resources"""
  697. if not self.done:
  698. try:
  699. if self.socket is not None:
  700. try:
  701. self.socket.shutdown(socket.SHUT_RDWR)
  702. except:
  703. pass
  704. finally:
  705. self.socket.close()
  706. finally:
  707. self.socket = self.read_buff = self.write_buff = self.protocol = None
  708. super(TCPROSTransport, self).close()