ntrip_client.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import ssl
4 import time
5 import base64
6 import socket
7 import select
8 import logging
9 
10 from .ntrip_base import NTRIPBase
11 
12 _CHUNK_SIZE = 1024
13 _SOURCETABLE_RESPONSES = [
14  'SOURCETABLE 200 OK'
15 ]
16 _SUCCESS_RESPONSES = [
17  'ICY 200 OK',
18  'HTTP/1.0 200 OK',
19  'HTTP/1.1 200 OK'
20 ]
21 _UNAUTHORIZED_RESPONSES = [
22  '401'
23 ]
24 
26 
27  # Public constants
28  DEFAULT_RTCM_TIMEOUT_SECONDS = 4
29 
30  def __init__(self, host, port, mountpoint, ntrip_version, username, password, logerr=logging.error, logwarn=logging.warning, loginfo=logging.info, logdebug=logging.debug):
31  # Call the parent constructor
32  super().__init__(logerr, logwarn, loginfo, logdebug)
33 
34  # Save the server info
35  self._host = host
36  self._port = port
37  self._mountpoint = mountpoint
38  self._ntrip_version = ntrip_version
39  if username is not None and password is not None:
40  self._basic_credentials = base64.b64encode('{}:{}'.format(
41  username, password).encode('utf-8')).decode('utf-8')
42  else:
43  self._basic_credentials = None
44 
45  # Initialize this so we don't throw an exception when closing
46  self._raw_socket = None
47  self._server_socket = None
48 
49  # Public SSL configuration
50  self.ssl = False
51  self.cert = None
52  self.key = None
53  self.ca_cert = None
54 
55  # Private reconnect info
61  self._first_rtcm_received = False
63 
64  # Public reconnect info
66 
67  def connect(self):
68  # Create a socket object that we will use to connect to the server
69  self._server_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
70  self._server_socket.settimeout(5)
71 
72  # Connect the socket to the server
73  try:
74  self._server_socket.connect((self._host, self._port))
75  except Exception as e:
76  self._logerr('Unable to connect socket to server at http://{}:{}'.format(self._host, self._port))
77  self._logerr('Exception: {}'.format(str(e)))
78  return False
79 
80  # If SSL, wrap the socket
81  if self.ssl:
82  # Configre the context based on the config
83  self._ssl_context = ssl.create_default_context()
84  if self.cert:
85  self._ssl_context.load_cert_chain(self.cert, self.key)
86  if self.ca_cert:
87  self._ssl_context.load_verify_locations(self.ca_cert)
88 
89  # Save the old socket for later just in case, and create a new SSL socket
90  self._raw_socket = self._server_socket
91  self._server_socket = self._ssl_context.wrap_socket(self._raw_socket, server_hostname=self._host)
92 
93  # Send the HTTP Request
94  try:
95  self._server_socket.send(self._form_request())
96  except Exception as e:
97  self._logerr('Unable to send request to server at http://{}:{}'.format(self._host, self._port))
98  self._logerr('Exception: {}'.format(str(e)))
99  return False
100 
101  # Get the response from the server
102  response = ''
103  try:
104  response = self._server_socket.recv(_CHUNK_SIZE).decode('ISO-8859-1')
105  except Exception as e:
106  self._logerr('Unable to read response from server at http://{}:{}'.format(self._host, self._port))
107  self._logerr('Exception: {}'.format(str(e)))
108  return False
109 
110  # Properly handle the response
111  if any(success in response for success in _SUCCESS_RESPONSES):
112  self._connected = True
113 
114  # Some debugging hints about the kind of error we received
115  known_error = False
116  if any(sourcetable in response for sourcetable in _SOURCETABLE_RESPONSES):
117  self._logwarn('Received sourcetable response from the server. This probably means the mountpoint specified is not valid')
118  known_error = True
119  elif any(unauthorized in response for unauthorized in _UNAUTHORIZED_RESPONSES):
120  self._logwarn('Received unauthorized response from the server. Check your username, password, and mountpoint to make sure they are correct.')
121  known_error = True
122  elif not self._connected and (self._ntrip_version == None or self._ntrip_version == ''):
123  self._logwarn('Received unknown error from the server. Note that the NTRIP version was not specified in the launch file. This is not necesarilly the cause of this error, but it may be worth checking your NTRIP casters documentation to see if the NTRIP version needs to be specified.')
124  known_error = True
125 
126  # Wish we could just return from the above checks, but some casters return both a success and an error in the response
127  # If we received any known error, even if we received a success it should be considered a failure
128  if known_error or not self._connected:
129  self._logerr('Invalid response received from http://{}:{}/{}'.format(
130  self._host, self._port, self._mountpoint))
131  self._logerr('Response: {}'.format(response))
132  return False
133  else:
134  self._loginfo(
135  'Connected to http://{}:{}/{}'.format(self._host, self._port, self._mountpoint))
136  return True
137 
138 
139  def disconnect(self):
140  # Disconnect the socket
141  self._connected = False
142  try:
143  if self._server_socket:
144  self._server_socket.shutdown(socket.SHUT_RDWR)
145  if self._raw_socket:
146  self._raw_socket.shutdown(socket.SHUT_RDWR)
147  except Exception as e:
148  self._logdebug('Encountered exception when shutting down the socket. This can likely be ignored')
149  self._logdebug('Exception: {}'.format(str(e)))
150  try:
151  if self._server_socket:
152  self._server_socket.close()
153  if self._raw_socket:
154  self._raw_socket.close()
155  except Exception as e:
156  self._logdebug('Encountered exception when closing the socket. This can likely be ignored')
157  self._logdebug('Exception: {}'.format(str(e)))
158 
159  def send_nmea(self, sentence):
160  if not self._connected:
161  self._logwarn('NMEA sent before client was connected, discarding NMEA')
162  return
163 
164  # Not sure if this is the right thing to do, but python will escape the return characters at the end of the string, so do this manually
165  if sentence[-4:] == '\\r\\n':
166  sentence = sentence[:-4] + '\r\n'
167  elif sentence[-2:] != '\r\n':
168  sentence = sentence + '\r\n'
169 
170  # Check if it is a valid NMEA sentence
171  if not self.nmea_parser.is_valid_sentence(sentence):
172  self._logwarn("Invalid NMEA sentence, not sending to server")
173  return
174 
175  # Encode the data and send it to the socket
176  try:
177  self._server_socket.send(sentence.encode('utf-8'))
178  except Exception as e:
179  self._logwarn('Unable to send NMEA sentence to server.')
180  self._logwarn('Exception: {}'.format(str(e)))
181  self._nmea_send_failed_count += 1
183  self._logwarn("NMEA sentence failed to send to server {} times, restarting".format(self._nmea_send_failed_count))
184  self.reconnect()
185  self._nmea_send_failed_count = 0
186  self.send_nmea(sentence) # Try sending the NMEA sentence again
187 
188 
189  def recv_rtcm(self):
190  if not self._connected:
191  self._logwarn('RTCM requested before client was connected, returning empty list')
192  return []
193 
194  # If it has been too long since we received an RTCM packet, reconnect
195  if time.time() - self.rtcm_timeout_seconds >= self._recv_rtcm_last_packet_timestamp and self._first_rtcm_received:
196  self._logerr('RTCM data not received for {} seconds, reconnecting'.format(self.rtcm_timeout_seconds))
197  self.reconnect()
198  self._first_rtcm_received = False
199 
200  # Check if there is any data available on the socket
201  read_sockets, _, _ = select.select([self._server_socket], [], [], 0)
202  if not read_sockets:
203  return []
204 
205  # Since we only ever pass the server socket to the list of read sockets, we can just read from that
206  # Read all available data into a buffer
207  data = b''
208  while True:
209  try:
210  chunk = self._server_socket.recv(_CHUNK_SIZE)
211  data += chunk
212  if len(chunk) < _CHUNK_SIZE:
213  break
214  except Exception as e:
215  self._logerr('Error while reading {} bytes from socket'.format(_CHUNK_SIZE))
216  if not self._socket_is_open():
217  self._logerr('Socket appears to be closed. Reconnecting')
218  self.reconnect()
219  return []
220  break
221  self._logdebug('Read {} bytes'.format(len(data)))
222 
223  # If 0 bytes were read from the socket even though we were told data is available multiple times,
224  # it can be safely assumed that we can reconnect as the server has closed the connection
225  if len(data) == 0:
226  self._read_zero_bytes_count += 1
228  self._logwarn('Reconnecting because we received 0 bytes from the socket even though it said there was data available {} times'.format(self._read_zero_bytes_count))
229  self.reconnect()
230  self._read_zero_bytes_count = 0
231  return []
232  else:
233  # Looks like we received valid data, so note when the data was received
234  self._recv_rtcm_last_packet_timestamp = time.time()
235  self._first_rtcm_received = True
236 
237  # Send the data to the RTCM parser to parse it
238  return self.rtcm_parser.parse(data) if data else []
239 
240  def _form_request(self):
241  if self._ntrip_version != None and self._ntrip_version != '':
242  request_str = 'GET /{} HTTP/1.0\r\nNtrip-Version: {}\r\nUser-Agent: NTRIP ntrip_client_ros\r\n'.format(
243  self._mountpoint, self._ntrip_version)
244  else:
245  request_str = 'GET /{} HTTP/1.0\r\nUser-Agent: NTRIP ntrip_client_ros\r\n'.format(
246  self._mountpoint)
247  if self._basic_credentials is not None:
248  request_str += 'Authorization: Basic {}\r\n'.format(
249  self._basic_credentials)
250  request_str += '\r\n'
251  return request_str.encode('utf-8')
252 
253  def _socket_is_open(self):
254  try:
255  # this will try to read bytes without blocking and also without removing them from buffer (peek only)
256  data = self._server_socket.recv(_CHUNK_SIZE, socket.MSG_DONTWAIT | socket.MSG_PEEK)
257  if len(data) == 0:
258  return False
259  except BlockingIOError:
260  return True # socket is open and reading from it would block
261  except ConnectionResetError:
262  self._logwarn('Connection reset by peer')
263  return False # socket was closed for some other reason
264  except socket.timeout:
265  return True # timeout likely means that the socket is still open
266  except Exception as e:
267  self._logwarn('Socket appears to be closed')
268  self._logwarn('Exception: {}'.format(e))
269  return False
270  return True
ntrip_client.ntrip_client.NTRIPClient.rtcm_timeout_seconds
rtcm_timeout_seconds
Definition: ntrip_client.py:65
ntrip_client.ntrip_client.NTRIPClient._ntrip_version
_ntrip_version
Definition: ntrip_client.py:38
ntrip_client.ntrip_base.NTRIPBase
Definition: ntrip_base.py:7
ntrip_client.ntrip_client.NTRIPClient._form_request
def _form_request(self)
Definition: ntrip_client.py:240
ntrip_client.ntrip_base.NTRIPBase.reconnect
def reconnect(self)
Definition: ntrip_base.py:48
ntrip_client.ntrip_base.NTRIPBase.rtcm_parser
rtcm_parser
Definition: ntrip_base.py:21
ntrip_client.ntrip_client.NTRIPClient._ssl_context
_ssl_context
Definition: ntrip_client.py:83
ntrip_client.ntrip_client.NTRIPClient._read_zero_bytes_max
_read_zero_bytes_max
Definition: ntrip_client.py:60
ntrip_client.ntrip_client.NTRIPClient._recv_rtcm_last_packet_timestamp
_recv_rtcm_last_packet_timestamp
Definition: ntrip_client.py:62
ntrip_client.ntrip_client.NTRIPClient._socket_is_open
def _socket_is_open(self)
Definition: ntrip_client.py:253
ntrip_client.ntrip_client.NTRIPClient
Definition: ntrip_client.py:25
ntrip_client.ntrip_client.NTRIPClient.recv_rtcm
def recv_rtcm(self)
Definition: ntrip_client.py:189
ntrip_client.ntrip_base.NTRIPBase._connected
_connected
Definition: ntrip_base.py:36
ntrip_client.ntrip_client.NTRIPClient._nmea_send_failed_max
_nmea_send_failed_max
Definition: ntrip_client.py:58
ntrip_client.ntrip_client.NTRIPClient._basic_credentials
_basic_credentials
Definition: ntrip_client.py:40
ntrip_client.ntrip_base.NTRIPBase._loginfo
_loginfo
Definition: ntrip_base.py:17
ntrip_client.ntrip_base.NTRIPBase._logerr
_logerr
Definition: ntrip_base.py:15
ntrip_client.ntrip_client.NTRIPClient._first_rtcm_received
_first_rtcm_received
Definition: ntrip_client.py:61
ntrip_client.ntrip_base.NTRIPBase._reconnect_attempt_count
_reconnect_attempt_count
Definition: ntrip_base.py:58
ntrip_client.ntrip_base.NTRIPBase.send_nmea
def send_nmea(self)
Definition: ntrip_base.py:66
ntrip_client.ntrip_client.NTRIPClient._nmea_send_failed_count
_nmea_send_failed_count
Definition: ntrip_client.py:57
ntrip_client.ntrip_client.NTRIPClient._mountpoint
_mountpoint
Definition: ntrip_client.py:37
ntrip_client.ntrip_client.NTRIPClient._server_socket
_server_socket
Definition: ntrip_client.py:47
ntrip_client.ntrip_base.NTRIPBase._logwarn
_logwarn
Definition: ntrip_base.py:16
ntrip_client.ntrip_client.NTRIPClient.cert
cert
Definition: ntrip_client.py:51
ntrip_client.ntrip_client.NTRIPClient._read_zero_bytes_count
_read_zero_bytes_count
Definition: ntrip_client.py:59
ntrip_client.ntrip_base.NTRIPBase.nmea_parser
nmea_parser
Definition: ntrip_base.py:27
ntrip_client.ntrip_client.NTRIPClient.ca_cert
ca_cert
Definition: ntrip_client.py:53
ntrip_client.ntrip_client.NTRIPClient.connect
def connect(self)
Definition: ntrip_client.py:67
ntrip_client.ntrip_client.NTRIPClient.send_nmea
def send_nmea(self, sentence)
Definition: ntrip_client.py:159
ntrip_client.ntrip_client.NTRIPClient._host
_host
Definition: ntrip_client.py:35
ntrip_client.ntrip_client.NTRIPClient.DEFAULT_RTCM_TIMEOUT_SECONDS
int DEFAULT_RTCM_TIMEOUT_SECONDS
Definition: ntrip_client.py:28
ntrip_client.ntrip_client.NTRIPClient.disconnect
def disconnect(self)
Definition: ntrip_client.py:139
ntrip_client.ntrip_client.NTRIPClient._raw_socket
_raw_socket
Definition: ntrip_client.py:46
ntrip_client.ntrip_base.NTRIPBase._logdebug
_logdebug
Definition: ntrip_base.py:18
ntrip_client.ntrip_client.NTRIPClient.__init__
def __init__(self, host, port, mountpoint, ntrip_version, username, password, logerr=logging.error, logwarn=logging.warning, loginfo=logging.info, logdebug=logging.debug)
Definition: ntrip_client.py:30
ntrip_client.ntrip_base.NTRIPBase.shutdown
def shutdown(self)
Definition: ntrip_base.py:72
ntrip_client.ntrip_client.NTRIPClient.ssl
ssl
Definition: ntrip_client.py:50
ntrip_client.ntrip_client.NTRIPClient.key
key
Definition: ntrip_client.py:52
ntrip_client.ntrip_client.NTRIPClient._port
_port
Definition: ntrip_client.py:36


ntrip_client
Author(s): Parker Hannifin Corp
autogenerated on Sat Dec 21 2024 03:32:07