1313import re
1414import platform
1515from pymavlink import mavexpression
16+ import ssl
1617
1718# We want to re-export x25crc here
1819from pymavlink .generator .mavcrc import x25crc as x25crc
@@ -1853,8 +1854,9 @@ def write(self, buf):
18531854 self .close_port ()
18541855 pass
18551856
1857+
18561858class mavwebsocket_client (mavfile ):
1857- '''client using WebSocket over TCP'''
1859+ '''client using WebSocket over TCP with WS and WSS support '''
18581860 def __init__ (self ,
18591861 device ,
18601862 source_system = 255 ,
@@ -1863,15 +1865,17 @@ def __init__(self,
18631865 use_native = default_native ):
18641866 self .resource = "/"
18651867 a = device .split (':' )
1866- if len (a ) < 2 :
1867- raise ValueError ("TCP ports must be specified as host:port" )
1868- self .host = a [0 ]
1869- self .port = int (a [1 ])
1870- if len (a ) > 2 :
1871- self .resource = a [2 ]
1868+ protocol = a [0 ]
1869+ if len (a ) < 3 :
1870+ raise ValueError ("WebSocket ports must be specified as protocol:host:port" )
1871+ self .host = a [1 ]
1872+ self .port = int (a [2 ])
1873+ if len (a ) > 3 :
1874+ self .resource = a [3 ]
18721875 self .sock = None
1876+ self .use_ssl = protocol .lower () == 'wss'
18731877 self .connect ()
1874- mavfile .__init__ (self , self .sock .fileno (), "ws:" + device , source_system = source_system , source_component = source_component , use_native = use_native )
1878+ mavfile .__init__ (self , self .sock .fileno (), protocol + device , source_system = source_system , source_component = source_component , use_native = use_native )
18751879
18761880 def connect (self ):
18771881 self .close ()
@@ -1883,20 +1887,42 @@ def connect(self):
18831887 BytesMessage ,
18841888 )
18851889 try :
1886- self .sock = socket .create_connection ((self .host , self .port ))
1890+ # Create basic socket connection
1891+ raw_sock = socket .create_connection ((self .host , self .port ))
1892+
1893+ # Wrap with SSL if using WSS
1894+ if self .use_ssl :
1895+ context = ssl .create_default_context ()
1896+ # Optional: For testing with self-signed certificates, uncomment:
1897+ # context.check_hostname = False
1898+ # context.verify_mode = ssl.CERT_NONE
1899+ self .sock = context .wrap_socket (raw_sock , server_hostname = self .host )
1900+ else :
1901+ self .sock = raw_sock
1902+
18871903 except socket .error as e :
1888- if e .errno in [ errno .ECONNREFUSED , errno .EHOSTUNREACH ]:
1904+ if e .errno in [errno .ECONNREFUSED , errno .EHOSTUNREACH ]:
18891905 return
18901906 raise
1907+ except ssl .SSLError as e :
1908+ print (f"SSL Error: { e } " )
1909+ raise
1910+
18911911 self .sock .setblocking (1 )
18921912 self .ws = WSConnection (ConnectionType .CLIENT )
18931913 b = self .ws .send (Request (host = self .host , target = self .resource ))
18941914 self .sock .send (b )
18951915 self .buffer = b''
1896-
1916+
18971917 # wait for handshake response
18981918 while True :
1899- data = self .sock .recv (4096 )
1919+ try :
1920+ data = self .sock .recv (4096 )
1921+ except ssl .SSLError as e :
1922+ raise RuntimeError (f"WebSocket SSL handshake failed: { e } " )
1923+ except socket .error as e :
1924+ raise RuntimeError (f"WebSocket handshake failed: { e } " )
1925+
19001926 if not data :
19011927 raise RuntimeError ("WebSocket handshake failed" )
19021928 self .ws .receive_data (data )
@@ -1905,7 +1931,7 @@ def connect(self):
19051931 self .sock .setblocking (0 )
19061932 return
19071933
1908- def recv (self ,n = None ):
1934+ def recv (self , n = None ):
19091935 from wsproto .events import (
19101936 BytesMessage ,
19111937 CloseConnection
@@ -1918,10 +1944,22 @@ def recv(self,n=None):
19181944 return out
19191945 try :
19201946 data = self .sock .recv (n )
1947+ except ssl .SSLError as e :
1948+ # Handle SSL-specific errors
1949+ if e .errno == ssl .SSL_ERROR_WANT_READ :
1950+ return b"" # Need more data, try again later
1951+ elif e .errno == ssl .SSL_ERROR_WANT_WRITE :
1952+ return b"" # SSL needs to write, try again later
1953+ elif e .errno in [errno .EAGAIN , errno .EWOULDBLOCK ]:
1954+ return b""
1955+ else :
1956+ # Real SSL error, reconnect
1957+ self .connect ()
1958+ return b''
19211959 except socket .error as e :
1922- if e .errno in [ errno .EAGAIN , errno .EWOULDBLOCK ]:
1960+ if e .errno in [errno .EAGAIN , errno .EWOULDBLOCK ]:
19231961 return b""
1924- if e .errno in [ errno .ECONNRESET , errno .EPIPE ]:
1962+ if e .errno in [errno .ECONNRESET , errno .EPIPE ]:
19251963 self .connect ()
19261964 return b''
19271965 raise
@@ -1944,16 +1982,26 @@ def write(self, data):
19441982 b = self .ws .send (BytesMessage (data = data ))
19451983 try :
19461984 self .sock .send (b )
1985+ except ssl .SSLError as e :
1986+ # Handle SSL-specific errors
1987+ if e .errno == ssl .SSL_ERROR_WANT_READ :
1988+ return # SSL needs to read, try again later
1989+ elif e .errno == ssl .SSL_ERROR_WANT_WRITE :
1990+ return # SSL needs to write, try again later
1991+ else :
1992+ # Real SSL error, reconnect
1993+ self .connect ()
19471994 except socket .error as e :
1948- if e .errno in [ errno .EPIPE ]:
1995+ if e .errno in [errno .EPIPE ]:
19491996 self .connect ()
19501997 pass
19511998
19521999 def close (self ):
19532000 if self .sock :
19542001 self .sock .close ()
19552002 self .sock = None
1956-
2003+
2004+
19572005def mavlink_connection (device , baud = 115200 , source_system = 255 , source_component = 0 ,
19582006 planner_format = None , write = False , append = False ,
19592007 robust_parsing = True , notimestamps = False , input = True ,
@@ -1987,8 +2035,8 @@ def mavlink_connection(device, baud=115200, source_system=255, source_component=
19872035 return mavudp (device [9 :], input = False , source_system = source_system , source_component = source_component , use_native = use_native , broadcast = True )
19882036 if device .startswith ('wsserver:' ):
19892037 return mavwebsocket (device [9 :], source_system = source_system , source_component = source_component , use_native = use_native )
1990- if device .startswith ('ws:' ):
1991- return mavwebsocket_client (device [ 3 :] , source_system = source_system , source_component = source_component , use_native = use_native )
2038+ if device .startswith ('ws:' ) or device . startswith ( 'wss:' ) :
2039+ return mavwebsocket_client (device , source_system = source_system , source_component = source_component , use_native = use_native )
19922040 # For legacy purposes we accept the following syntax and let the caller to specify direction
19932041 if device .startswith ('udp:' ):
19942042 return mavudp (device [4 :], input = input , source_system = source_system , source_component = source_component , use_native = use_native )
0 commit comments