10 from .ntrip_base
import NTRIPBase
13 _SOURCETABLE_RESPONSES = [
16 _SUCCESS_RESPONSES = [
21 _UNAUTHORIZED_RESPONSES = [
28 DEFAULT_RTCM_TIMEOUT_SECONDS = 4
30 def __init__(self, host, port, mountpoint, ntrip_version, username, password, logerr=logging.error, logwarn=logging.warning, loginfo=logging.info, logdebug=logging.debug):
32 super().
__init__(logerr, logwarn, loginfo, logdebug)
39 if username
is not None and password
is not None:
41 username, password).encode(
'utf-8')).decode(
'utf-8')
69 self.
_server_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
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)))
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)))
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)))
111 if any(success
in response
for success
in _SUCCESS_RESPONSES):
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')
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.')
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.')
129 self.
_logerr(
'Invalid response received from http://{}:{}/{}'.format(
131 self.
_logerr(
'Response: {}'.format(response))
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)))
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)))
161 self.
_logwarn(
'NMEA sent before client was connected, discarding NMEA')
165 if sentence[-4:] ==
'\\r\\n':
166 sentence = sentence[:-4] +
'\r\n'
167 elif sentence[-2:] !=
'\r\n':
168 sentence = sentence +
'\r\n'
171 if not self.
nmea_parser.is_valid_sentence(sentence):
172 self.
_logwarn(
"Invalid NMEA sentence, not sending to server")
178 except Exception
as e:
179 self.
_logwarn(
'Unable to send NMEA sentence to server.')
180 self.
_logwarn(
'Exception: {}'.format(str(e)))
191 self.
_logwarn(
'RTCM requested before client was connected, returning empty list')
201 read_sockets, _, _ = select.select([self.
_server_socket], [], [], 0)
212 if len(chunk) < _CHUNK_SIZE:
214 except Exception
as e:
215 self.
_logerr(
'Error while reading {} bytes from socket'.format(_CHUNK_SIZE))
217 self.
_logerr(
'Socket appears to be closed. Reconnecting')
221 self.
_logdebug(
'Read {} bytes'.format(len(data)))
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))
238 return self.
rtcm_parser.parse(data)
if data
else []
242 request_str =
'GET /{} HTTP/1.0\r\nNtrip-Version: {}\r\nUser-Agent: NTRIP ntrip_client_ros\r\n'.format(
245 request_str =
'GET /{} HTTP/1.0\r\nUser-Agent: NTRIP ntrip_client_ros\r\n'.format(
248 request_str +=
'Authorization: Basic {}\r\n'.format(
250 request_str +=
'\r\n'
251 return request_str.encode(
'utf-8')
256 data = self.
_server_socket.recv(_CHUNK_SIZE, socket.MSG_DONTWAIT | socket.MSG_PEEK)
259 except BlockingIOError:
261 except ConnectionResetError:
262 self.
_logwarn(
'Connection reset by peer')
264 except socket.timeout:
266 except Exception
as e:
267 self.
_logwarn(
'Socket appears to be closed')
268 self.
_logwarn(
'Exception: {}'.format(e))