Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Only connect to server, if our own publisher has listeners #48

Open
wants to merge 1 commit into
base: ros
Choose a base branch
from
Open
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
17 changes: 11 additions & 6 deletions scripts/ntrip_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,6 @@ 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

# Setup our subscriber
self._nmea_sub = rospy.Subscriber('nmea', Sentence, self.subscribe_nmea, queue_size=10)

Expand All @@ -141,9 +136,19 @@ def stop(self):

def subscribe_nmea(self, nmea):
# Just extract the NMEA from the message, and send it right to the server
self._client.send_nmea(nmea.sentence)
if self._client._connected:
self._client.send_nmea(nmea.sentence)

def publish_rtcm(self, event):
if self._rtcm_pub.get_num_connections()==0:
if self._client._connected:
self._client.disconnect()
return
if not self._client._connected:
# Connect the client
if not self._client.connect():
rospy.logerr('Unable to connect to NTRIP server')
return
for raw_rtcm in self._client.recv_rtcm():
self._rtcm_pub.publish(self._create_rtcm_message(raw_rtcm))

Expand Down