Пример #1
0
    def receive_loop(self, msgs_callback):
        """
        Receive messages until shutdown
        @param msgs_callback: callback to invoke for new messages received    
        @type  msgs_callback: fn([msg])
        """
        # - use assert here as this would be an internal error, aka bug
        logger.debug("receive_loop for [%s]", self.name)
        try:
            try:
                while not self.done and not is_shutdown():
                    msgs = self.receive_once()
                    if not self.done and not is_shutdown():
                        msgs_callback(msgs)

                rospydebug("receive_loop[%s]: done condition met, exited loop"%self.name)
            except DeserializationError as e:
                logerr("[%s] error deserializing incoming request: %s"%self.name, str(e))
                rospyerr("[%s] error deserializing incoming request: %s"%self.name, traceback.format_exc())                 
            except:
                # in many cases this will be a normal hangup, but log internally
                try:
                    #1467 sometimes we get exceptions due to
                    #interpreter shutdown, so blanket ignore those if
                    #the reporting fails
                    rospydebug("exception in receive loop for [%s], may be normal. Exception is %s",self.name, traceback.format_exc())                    
                except: pass
        finally:
            if not self.done:
                self.close()
Пример #2
0
def robust_connect_subscriber(conn, dest_addr, dest_port, pub_uri, receive_cb, resolved_topic_name):
    """
    Keeps trying to create connection for subscriber.  Then passes off to receive_loop once connected.
    """
    # kwc: this logic is not very elegant.  I am waiting to rewrite
    # the I/O loop with async i/o to clean this up.
    
    # timeout is really generous. for now just choosing one that is large but not infinite
    interval = 0.5
    while conn.socket is None and not conn.done and not rospy.is_shutdown():
        try:
            conn.connect(dest_addr, dest_port, pub_uri, timeout=60.)
        except rospy.exceptions.TransportInitError as e:
            # if the connection was closed intentionally
            # because of an unknown error, stop trying
            if conn.protocol is None:
                conn.done = True
                break
            rospyerr("unable to create subscriber transport: %s.  Will try again in %ss", e, interval)
            interval = interval * 2
            time.sleep(interval)
            
            # check to see if publisher state has changed
            conn.done = not check_if_still_publisher(resolved_topic_name, pub_uri)
	
    if not conn.done:
        conn.receive_loop(receive_cb)	    
Пример #3
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)
            
            s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
        except TransportInitError as tie:
            rospyerr("Unable to initiate TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))            
            raise
        except Exception as e:
            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))            

            # FATAL: no reconnection as error is unknown
            self.done = True
            if self.socket:
                try:
                    self.socket.shutdown(socket.SHUT_RDWR)
                except:
                    pass
                finally:
                    self.socket.close()
            self.socket = None
            
            raise TransportInitError(str(e)) #re-raise i/o error
Пример #4
0
 def _tcp_server_callback(self, sock, client_addr):
     """
     TCPServer callback: detects incoming topic or service connection and passes connection accordingly
 
     @param sock: socket connection
     @type  sock: socket.socket
     @param client_addr: client address
     @type  client_addr: (str, int)
     @raise TransportInitError: If transport cannot be succesfully initialized
     """
     #TODOXXX:rewrite this logic so it is possible to create TCPROSTransport object first, set its protocol,
     #and then use that to do the writing
     try:
         buff_size = 4096 # size of read buffer
         if python3 == 0:
             #initialize read_ros_handshake_header with BytesIO for Python 3 (instead of bytesarray())    
             header = read_ros_handshake_header(sock, StringIO(), buff_size)
         else:
             header = read_ros_handshake_header(sock, BytesIO(), buff_size)
         
         if 'topic' in header:
             err_msg = self.topic_connection_handler(sock, client_addr, header)
         elif 'service' in header:
             err_msg = self.service_connection_handler(sock, client_addr, header)
         else:
             err_msg = 'no topic or service name detected'
         if err_msg:
             # shutdown race condition: nodes that come up and down
             # quickly can receive connections during teardown.
             
             # We use is_shutdown_requested() because we can get
             # into bad connection states during client shutdown
             # hooks.
             if not rospy.core.is_shutdown_requested():
                 write_ros_handshake_header(sock, {'error' : err_msg})
                 raise TransportInitError("Could not process inbound connection: "+err_msg+str(header))
             else:
                 write_ros_handshake_header(sock, {'error' : 'node shutting down'})
                 return
     except rospy.exceptions.TransportInitError as e:
         logwarn(str(e))
         if sock is not None:
             sock.close()
     except Exception as e:
         # collect stack trace separately in local log file
         if not rospy.core.is_shutdown_requested():
             logwarn("Inbound TCP/IP connection failed: %s", e)
             rospyerr("Inbound TCP/IP connection failed:\n%s", traceback.format_exc())
         if sock is not None:
             sock.close()
Пример #5
0
def robust_connect_subscriber(conn, dest_addr, dest_port, pub_uri, receive_cb):
    """
    Keeps trying to create connection for subscriber.  Then passes off to receive_loop once connected.
    """
    # kwc: this logic is not very elegant.  I am waiting to rewrite
    # the I/O loop with async i/o to clean this up.
    
    # timeout is really generous. for now just choosing one that is large but not infinite
    interval = 0.5
    while conn.socket is None and not conn.done and not rospy.is_shutdown():
        try:
            conn.connect(dest_addr, dest_port, pub_uri, timeout=60.)
        except rospy.exceptions.TransportInitError as e:
            rospyerr("unable to create subscriber transport: %s.  Will try again in %ss", e, interval)
            interval = interval * 2
            time.sleep(interval)
	
    conn.receive_loop(receive_cb)	    
Пример #6
0
    def receive_once(self):
        """
        block until messages are read off of socket
        @return: list of newly received messages
        @rtype: [Msg]
        @raise TransportException: if unable to receive message due to error
        """
        sock = self.socket
        if sock is None:
            raise TransportException("connection not initialized")
        b = self.read_buff
        msg_queue = []
        p = self.protocol
        try:
            sock.setblocking(1)                
            while not msg_queue and not self.done and not is_shutdown():
                if b.tell() >= 4:
                    p.read_messages(b, msg_queue, sock) 
                if not msg_queue:
                    self.stat_bytes += recv_buff(sock, b, p.buff_size)
            self.stat_num_msg += len(msg_queue) #STATS
            # set the _connection_header field
            for m in msg_queue:
                m._connection_header = self.header
                
            # #1852: keep track of last latched message
            if self.is_latched and msg_queue:
                self.latch = msg_queue[-1]
            
            return msg_queue

        except DeserializationError as e:
            rospyerr(traceback.format_exc())            
            raise TransportException("receive_once[%s]: DeserializationError %s"%(self.name, str(e)))
        except TransportTerminated as e:
            raise #reraise
        except ServiceException as e:
            raise
        except Exception as e:
            rospyerr(traceback.format_exc())
            raise TransportException("receive_once[%s]: unexpected error %s"%(self.name, str(e)))
        return retval
Пример #7
0
    def create_transport(self, resolved_name, pub_uri, protocol_params):
        """
        Connect to topic resolved_name on Publisher pub_uri using TCPROS.
        @param resolved_name str: resolved topic name
        @type  resolved_name: str
        @param pub_uri: XML-RPC URI of publisher 
        @type  pub_uri: str
        @param protocol_params: protocol parameters to use for connecting
        @type protocol_params: [XmlRpcLegal]
        @return: code, message, debug
        @rtype: (int, str, int)
        """

        # Validate protocol params = [TCPROS, address, port]
        if type(protocol_params) != list or len(protocol_params) != 3:
            return 0, "ERROR: invalid TCPROS parameters", 0
        if protocol_params[0] != TCPROS:
            return 0, "INTERNAL ERROR: protocol id is not TCPROS: %s" % id, 0
        id, dest_addr, dest_port = protocol_params

        sub = self.topic_manager.get_subscriber_impl(resolved_name)

        # Create connection
        try:
            protocol = TCPROSSub(
                resolved_name,
                sub.data_class,
                queue_size=sub.queue_size,
                buff_size=sub.buff_size,
                tcp_nodelay=sub.tcp_nodelay,
            )
            conn = TCPROSTransport(protocol, resolved_name)
            # timeout is really generous. for now just choosing one that is large but not infinite
            conn.connect(dest_addr, dest_port, pub_uri, timeout=60.0)
            t = threading.Thread(name=resolved_name, target=conn.receive_loop, args=(sub.receive_callback,))
            # don't enable this just yet, need to work on this logic
            # rospy.core._add_shutdown_thread(t)
            t.start()
        except rospy.exceptions.TransportInitError, e:
            rospyerr("unable to create subscriber transport: %s", e)
            return 0, "Internal error creating inbound TCP connection for [%s]: %s" % (resolved_name, e), -1
Пример #8
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        # first make sure that if ROS_HOSTNAME=localhost, we will not attempt
        # to connect to anything other than localhost
        if ("ROS_HOSTNAME" in os.environ) and (os.environ["ROS_HOSTNAME"]
                                               == "localhost"):
            if not rosgraph.network.is_local_address(dest_addr):
                msg = "attempted to connect to non-local host [%s] from a node launched with ROS_HOSTNAME=localhost" % (
                    dest_addr)
                logwarn(msg)
                self.close()
                raise TransportInitError(msg)  # bubble up

        # now we can proceed with trying to connect.
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)
            if rosgraph.network.use_ipv6():
                s = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
            else:
                s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            logdebug('connecting to ' + str(dest_addr) + ' ' + str(dest_port))
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
            self.local_endpoint = self.socket.getsockname()
            self.remote_endpoint = (dest_addr, dest_port)
        except TransportInitError as tie:
            rospyerr(
                "Unable to initiate TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            raise
        except Exception as e:
            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn(
                "Unknown error initiating TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            # check for error type and reason. On unknown errors the socket will be closed
            # to avoid reconnection and error reproduction
            if not isinstance(e, socket.error):
                # FATAL: no reconnection as error is unknown
                self.close()
            elif not isinstance(e, socket.timeout) and e.errno not in [
                    errno.ENETDOWN, errno.ENETUNREACH, errno.ENETRESET,
                    errno.ECONNABORTED, errno.ETIMEDOUT, errno.EHOSTDOWN,
                    errno.EHOSTUNREACH
            ]:
                # reconnect in follow cases, otherwise close the socket:
                # 1. socket.timeout: on timeouts caused by delays on wireless links
                # 2. ENETDOWN (100), ENETUNREACH (101), ENETRESET (102), ECONNABORTED (103):
                #     while using ROS_HOSTNAME ros binds to a specific interface. Theses errors
                #     are thrown on interface shutdown e.g. on reconnection in LTE networks
                # 3. ETIMEDOUT (110): same like 1. (for completeness)
                # 4. EHOSTDOWN (112), EHOSTUNREACH (113): while network and/or DNS-server is not reachable
                #
                # no reconnection as error is not 1.-4.
                self.close()
            raise TransportInitError(str(e))  #re-raise i/o error
Пример #9
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        # first make sure that if ROS_HOSTNAME=localhost, we will not attempt
        # to connect to anything other than localhost
        if ("ROS_HOSTNAME" in os.environ) and (os.environ["ROS_HOSTNAME"] == "localhost"):
          if not rosgraph.network.is_local_address(dest_addr):
            msg = "attempted to connect to non-local host [%s] from a node launched with ROS_HOSTNAME=localhost" % (dest_addr)
            logwarn(msg)
            self.close()
            raise TransportInitError(msg)  # bubble up
 
        # now we can proceed with trying to connect.
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)
            if rosgraph.network.use_ipv6():
                s = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
            else:
                s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            logdebug('connecting to ' + str(dest_addr)+ ' ' + str(dest_port))
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
            self.local_endpoint = self.socket.getsockname()
            self.remote_endpoint = (dest_addr, dest_port)
        except TransportInitError as tie:
            rospyerr("Unable to initiate TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))            
            raise
        except Exception as e:
            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            # check for error type and reason. On unknown errors the socket will be closed
            # to avoid reconnection and error reproduction
            if not isinstance(e, socket.error):
                # FATAL: no reconnection as error is unknown
                self.close()
            elif not isinstance(e, socket.timeout) and e.errno not in [100, 101, 102, 103, 110, 112, 113]:
                # reconnect in follow cases, otherwise close the socket:
                # 1. socket.timeout: on timeouts caused by delays on wireless links
                # 2. ENETDOWN (100), ENETUNREACH (101), ENETRESET (102), ECONNABORTED (103):
                #     while using ROS_HOSTNAME ros binds to a specific interface. Theses errors
                #     are thrown on interface shutdown e.g. on reconnection in LTE networks
                # 3. ETIMEDOUT (110): same like 1. (for completeness)
                # 4. EHOSTDOWN (112), EHOSTUNREACH (113): while network and/or DNS-server is not reachable
                #
                # no reconnection as error is not 1.-4.
                self.close()
            raise TransportInitError(str(e)) #re-raise i/o error
Пример #10
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        # first make sure that if ROS_HOSTNAME=localhost, we will not attempt
        # to connect to anything other than localhost
        if ("ROS_HOSTNAME" in os.environ) and (os.environ["ROS_HOSTNAME"]
                                               == "localhost"):
            if not rosgraph.network.is_local_address(dest_addr):
                msg = "attempted to connect to non-local host [%s] from a node launched with ROS_HOSTNAME=localhost" % (
                    dest_addr)
                logwarn(msg)
                self.close()
                raise TransportInitError(msg)  # bubble up

        # now we can proceed with trying to connect.
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)
            if rosgraph.network.use_ipv6():
                s = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
            else:
                s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            logdebug('connecting to ' + str(dest_addr) + ' ' + str(dest_port))
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
            self.local_endpoint = self.socket.getsockname()
            self.remote_endpoint = (dest_addr, dest_port)
        except TransportInitError as tie:
            rospyerr(
                "Unable to initiate TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            raise
        except Exception as e:
            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn(
                "Unknown error initiating TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))

            # FATAL: no reconnection as error is unknown
            self.close()
            raise TransportInitError(str(e))  #re-raise i/o error
Пример #11
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)

            s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
        except TransportInitError as tie:
            rospyerr(
                "Unable to initiate TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            raise
        except Exception as e:
            # FATAL: no reconnection as error is unknown
            self.done = True
            if self.socket:
                try:
                    self.socket.shutdown()
                except:
                    pass
                finally:
                    self.socket.close()
            self.socket = None

            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn(
                "Unknown error initiating TCP/IP socket to %s:%s (%s): %s" %
                (dest_addr, dest_port, endpoint_id, traceback.format_exc()))
            raise TransportInitError(str(e))  #re-raise i/o error
Пример #12
0
    def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
        """
        Establish TCP connection to the specified
        address/port. connect() always calls L{write_header()} and
        L{read_header()} after the connection is made
        @param dest_addr: destination IP address
        @type  dest_addr: str
        @param dest_port: destination port
        @type  dest_port: int                
        @param endpoint_id: string identifier for connection (for statistics)
        @type  endpoint_id: str
        @param timeout: (optional keyword) timeout in seconds
        @type  timeout: float
        @raise TransportInitError: if unable to create connection
        """
        # first make sure that if ROS_HOSTNAME=localhost, we will not attempt
        # to connect to anything other than localhost
        if ("ROS_HOSTNAME" in os.environ) and (os.environ["ROS_HOSTNAME"] == "localhost"):
          if not rosgraph.network.is_local_address(dest_addr):
            msg = "attempted to connect to non-local host [%s] from a node launched with ROS_HOSTNAME=localhost" % (dest_addr)
            logwarn(msg)
            self.close()
            raise TransportInitError(msg)  # bubble up
 
        # now we can proceed with trying to connect.
        try:
            self.endpoint_id = endpoint_id
            self.dest_address = (dest_addr, dest_port)
            if rosgraph.network.use_ipv6():
                s = socket.socket(socket.AF_INET6, socket.SOCK_STREAM)
            else:
                s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
            if _is_use_tcp_keepalive():
                # OSX (among others) does not define these options
                if hasattr(socket, 'TCP_KEEPCNT') and \
                   hasattr(socket, 'TCP_KEEPIDLE') and \
                   hasattr(socket, 'TCP_KEEPINTVL'):
                    # turn on KEEPALIVE
                    s.setsockopt(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)
                    # - # keepalive failures before actual connection failure
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPCNT, 9)
                    # - timeout before starting KEEPALIVE process
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPIDLE, 60)
                    # - interval to send KEEPALIVE after IDLE timeout
                    s.setsockopt(socket.SOL_TCP, socket.TCP_KEEPINTVL, 10)
            if timeout is not None:
                s.settimeout(timeout)
            self.socket = s
            logdebug('connecting to ' + str(dest_addr)+ ' ' + str(dest_port))
            self.socket.connect((dest_addr, dest_port))
            self.write_header()
            self.read_header()
            self.local_endpoint = self.socket.getsockname()
            self.remote_endpoint = (dest_addr, dest_port)
        except TransportInitError as tie:
            rospyerr("Unable to initiate TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))            
            raise
        except Exception as e:
            #logerr("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, str(e)))
            rospywarn("Unknown error initiating TCP/IP socket to %s:%s (%s): %s"%(dest_addr, dest_port, endpoint_id, traceback.format_exc()))            

            # FATAL: no reconnection as error is unknown
            self.close()
            raise TransportInitError(str(e)) #re-raise i/o error
Пример #13
0
    def receive_loop(self, msgs_callback):
        """
        Receive messages until shutdown
        @param msgs_callback: callback to invoke for new messages received    
        @type  msgs_callback: fn([msg])
        """
        # - use assert here as this would be an internal error, aka bug
        logger.debug("receive_loop for [%s]", self.name)
        # Start a callback thread to process the callbacks. This way the
        # receive loop can continue calling recv() while a long-running
        # callback is running.
        try:
            self.msg_queue = []
            self.msg_queue_lock = threading.Lock()
            self.msg_queue_condition = threading.Condition(self.msg_queue_lock)
            callback_thread = threading.Thread(
                    target=self.callback_loop,
                    args=(msgs_callback,))
            callback_thread.start()
            while not self.done and not is_shutdown():
                try:
                    if self.socket is not None:
                        msgs = self.receive_once()
                        if not self.done and not is_shutdown():
                            with self.msg_queue_lock:
                                self.msg_queue += msgs
                                if self.protocol.queue_size is not None:
                                    self.msg_queue = self.msg_queue[-self.protocol.queue_size:]
                                self.msg_queue_condition.notify()
                    else:
                        self._reconnect()

                except TransportException as e:
                    # set socket to None so we reconnect
                    try:
                        if self.socket is not None:
                            try:
                                self.socket.shutdown()
                            except:
                                pass
                            finally:
                                self.socket.close()
                    except:
                        pass
                    self.socket = None

                except DeserializationError as e:
                    #TODO: how should we handle reconnect in this case?
                    
                    logerr("[%s] error deserializing incoming request: %s"%(self.name, str(e)))
                    rospyerr("[%s] error deserializing incoming request: %s"%(self.name, traceback.format_exc()))
                except:
                    # in many cases this will be a normal hangup, but log internally
                    try:
                        #1467 sometimes we get exceptions due to
                        #interpreter shutdown, so blanket ignore those if
                        #the reporting fails
                        rospydebug("exception in receive loop for [%s], may be normal. Exception is %s",self.name, traceback.format_exc())                    
                    except: pass
            with self.msg_queue_lock:
                self.msg_queue_condition.notify()
            callback_thread.join()
            rospydebug("receive_loop[%s]: done condition met, exited loop"%self.name)                    
        finally:
            if not self.done:
                self.close()
Пример #14
0
                    write_ros_handshake_header(sock, {'error': err_msg})
                    raise TransportInitError(
                        "Could not process inbound connection: " + err_msg +
                        str(header))
                else:
                    write_ros_handshake_header(sock,
                                               {'error': 'node shutting down'})
                    return
        except rospy.exceptions.TransportInitError, e:
            logwarn(str(e))
            if sock is not None:
                sock.close()
        except Exception, e:
            # collect stack trace separately in local log file
            logwarn("Inbound TCP/IP connection failed: %s", e)
            rospyerr("Inbound TCP/IP connection failed:\n%s",
                     traceback.format_exc(e))
            if sock is not None:
                sock.close()


class TCPROSTransportProtocol(object):
    """
    Abstraction of TCPROS connections. Implementations Services/Publishers/Subscribers must implement this
    protocol, which defines how messages are deserialized from an inbound connection (read_messages()) as
    well as which fields to send when creating a new connection (get_header_fields()).
    """
    def __init__(self,
                 resolved_name,
                 recv_data_class,
                 queue_size=None,
                 buff_size=DEFAULT_BUFF_SIZE):