Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions launch/ntrip_client.launch
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@
<!-- Will affect how many times the node will attempt to reconnect before exiting, and how long it will wait in between attempts when a reconnect occurs -->
<param name="reconnect_attempt_max" value="10" />
<param name="reconnect_attempt_wait_seconds" value="5" />
<param name="reconnect_backoff_base" value="1.8" />
<param name="reconnect_backoff_max_seconds" value="300">

<!-- How many seconds is acceptable in between receiving RTCM. If RTCM is not received for this duration, the node will attempt to reconnect -->
<param name="rtcm_timeout_seconds" value="4" />
Expand Down
2 changes: 2 additions & 0 deletions launch/ntrip_serial_device.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
<!-- Will affect how many times the node will attempt to reconnect before exiting, and how long it will wait in between attempts when a reconnect occurs -->
<param name="reconnect_attempt_max" value="10" />
<param name="reconnect_attempt_wait_seconds" value="5" />
<param name="reconnect_backoff_base" value="1.8" />
<param name="reconnect_backoff_max_seconds" value="300">

<!-- Uncomment the following section and replace "/gx5/nmea/sentence" with the topic you are sending NMEA on if it is not the one we requested -->
<!--<remap from="/ntrip_client/nmea" to="/gx5/nmea/sentence" />-->
Expand Down
2 changes: 2 additions & 0 deletions scripts/ntrip_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ def __init__(self):
self._client.nmea_parser.nmea_min_length = self._nmea_min_length
self._client.reconnect_attempt_max = self._reconnect_attempt_max
self._client.reconnect_attempt_wait_seconds = self._reconnect_attempt_wait_seconds
self._client.reconnect_backoff_base = self._reconnect_backoff_base
self._client.reconnect_backoff_max_seconds = self._reconnect_backoff_max_seconds
self._client.rtcm_timeout_seconds = rospy.get_param('~rtcm_timeout_seconds', NTRIPClient.DEFAULT_RTCM_TIMEOUT_SECONDS)


Expand Down
2 changes: 2 additions & 0 deletions scripts/ntrip_serial_device_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ def __init__(self):
self._client.nmea_parser.nmea_min_length = self._nmea_min_length
self._client.reconnect_attempt_max = self._reconnect_attempt_max
self._client.reconnect_attempt_wait_seconds = self._reconnect_attempt_wait_seconds
self._client.reconnect_backoff_base = self._reconnect_backoff_base
self._client.reconnect_backoff_max_seconds = self._reconnect_backoff_max_seconds


if __name__ == '__main__':
Expand Down
64 changes: 47 additions & 17 deletions src/ntrip_client/ntrip_base.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
import time
import logging
import rospy

from .nmea_parser import NMEAParser
from .rtcm_parser import RTCMParser
Expand All @@ -10,6 +10,9 @@ class NTRIPBase:
DEFAULT_RECONNECT_ATTEMPT_MAX = 10
DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS = 5

DEFAULT_RECONNECT_BACKOFF_BASE = 1.8
DEFAULT_RECONNECT_BACKOFF_MAX_SECONDS = 300

def __init__(self, logerr=logging.error, logwarn=logging.warning, loginfo=logging.info, logdebug=logging.debug):
# Bit of a strange pattern here, but save the log functions so we can be agnostic of ROS
self._logerr = logerr
Expand All @@ -34,34 +37,61 @@ def __init__(self, logerr=logging.error, logwarn=logging.warning, loginfo=loggin
# Setup some state
self._shutdown = False
self._connected = False
# How many connection attempts have failed since we last connected?
# We don't consider connection successful until some valid data has been received.
self._reconnect_attempt_count = 0

# Public reconnect info
self.reconnect_attempt_max = self.DEFAULT_RECONNECT_ATTEMPT_MAX
self.reconnect_attempt_wait_seconds = self.DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS
self.reconnect_backoff_base = self.DEFAULT_RECONNECT_BACKOFF_BASE
self.reconnect_backoff_max_seconds = self.DEFAULT_RECONNECT_BACKOFF_MAX_SECONDS

def connect(self):
raise NotImplementedError("Must override connect")

def disconnect(self):
raise NotImplementedError("Must override disconnect")

def reconnect(self):
if self._connected:
while not self._shutdown:
self._reconnect_attempt_count += 1
self.disconnect()
connect_success = self.connect()
if not connect_success and self._reconnect_attempt_count < self.reconnect_attempt_max:
self._logerr('Reconnect failed. Retrying in {} seconds'.format(self.reconnect_attempt_wait_seconds))
time.sleep(self.reconnect_attempt_wait_seconds)
elif self._reconnect_attempt_count >= self.reconnect_attempt_max:
self._reconnect_attempt_count = 0
raise Exception("Reconnect was attempted {} times, but never succeeded".format(self._reconnect_attempt_count))
elif connect_success:
self._reconnect_attempt_count = 0
break
else:
def _compute_reconnect_wait_time(self):
"""
Compute a time to sleep before attempting to reconnect.

This is based on an exponential backoff, capped to a maximum.

All of the initial wait times, the maximum and the base are configurable.
"""
return min(
self.reconnect_attempt_wait_seconds * (self.reconnect_backoff_base ** self._reconnect_attempt_count ),
self.reconnect_backoff_max_seconds
)

def reconnect(self, initial = False):
if not (self._connected or initial):
self._logdebug('Reconnect called while not connected, ignoring')
return

while not self._shutdown:
if not initial:
# If this isn't our initial connection attempt,
# disconnect and wait a reconnection interval
self.disconnect()
to_wait = self._compute_reconnect_wait_time()
self._logerr(f"Reconnecting in {to_wait:.1f} seconds")
rospy.sleep(self._compute_reconnect_wait_time())

initial = False
self._reconnect_attempt_count += 1

connect_success = self.connect()
if connect_success:
break

if self._reconnect_attempt_count >= self.reconnect_attempt_max:
raise Exception("Reconnect was attempted {} times, but never succeeded".format(self._reconnect_attempt_count))

def mark_successful_connection(self):
self._reconnect_attempt_count = 0

def send_nmea(self):
raise NotImplementedError("Must override send_nmea")
Expand Down
9 changes: 7 additions & 2 deletions src/ntrip_client/ntrip_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ def __init__(self, host, port, mountpoint, ntrip_version, username, password, lo
self.ca_cert = None

# Private reconnect info
self._reconnect_attempt_count = 0
self._nmea_send_failed_count = 0
self._nmea_send_failed_max = 5
self._read_zero_bytes_count = 0
Expand Down Expand Up @@ -235,7 +234,13 @@ def recv_rtcm(self):
self._first_rtcm_received = True

# Send the data to the RTCM parser to parse it
return self.rtcm_parser.parse(data) if data else []
parsed_packets = self.rtcm_parser.parse(data) if data else []

if parsed_packets:
# now we've received a packet, we can happily say that we are successfully connected
self.mark_successful_connection()

return parsed_packets

def _form_request(self):
if self._ntrip_version != None and self._ntrip_version != '':
Expand Down
10 changes: 5 additions & 5 deletions src/ntrip_client/ntrip_ros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,15 +77,15 @@ def __init__(self, name):
self._nmea_min_length = rospy.get_param('~nmea_min_length', NMEA_DEFAULT_MIN_LENGTH)
self._reconnect_attempt_max = rospy.get_param('~reconnect_attempt_max', NTRIPBase.DEFAULT_RECONNECT_ATTEMPT_MAX)
self._reconnect_attempt_wait_seconds = rospy.get_param('~reconnect_attempt_wait_seconds', NTRIPBase.DEFAULT_RECONNECT_ATEMPT_WAIT_SECONDS)
self._reconnect_backoff_base = rospy.get_param('~reconnect_backoff_base', NTRIPBase.DEFAULT_RECONNECT_BACKOFF_BASE)
self._reconnect_backoff_max_seconds = rospy.get_param('~reconnect_backoff_max_seconds', NTRIPBase.DEFAULT_RECONNECT_BACKOFF_MAX_SECONDS)

def run(self):
# Setup a shutdown hook
rospy.on_shutdown(self.stop)

# Connect the client
if not self._client.connect():
rospy.logerr('Unable to connect to NTRIP server')
return 1
# Start the client's reconnection loop
self._client.reconnect(initial = True)

# Setup our subscriber
self._nmea_sub = rospy.Subscriber('nmea', Sentence, self.subscribe_nmea, queue_size=10)
Expand Down Expand Up @@ -173,4 +173,4 @@ def _create_rtcm_msgs_rtcm_message(self, rtcm):
frame_id=self._rtcm_frame_id
),
message=rtcm
)
)