12 _MAVROS_MSGS_NAME =
"mavros_msgs"
13 _RTCM_MSGS_NAME =
"rtcm_msgs"
14 have_mavros_msgs =
False
15 have_rtcm_msgs =
False
16 if importlib.util.find_spec(_MAVROS_MSGS_NAME)
is not None:
17 have_mavros_msgs =
True
18 from mavros_msgs.msg
import RTCM
as mavros_msgs_RTCM
19 if importlib.util.find_spec(_RTCM_MSGS_NAME)
is not None:
21 from rtcm_msgs.msg
import Message
as rtcm_msgs_RTCM
29 host = rospy.get_param(
'~host',
'127.0.0.1')
30 port = rospy.get_param(
'~port',
'2101')
31 mountpoint = rospy.get_param(
'~mountpoint',
'mount')
34 ntrip_version = rospy.get_param(
'~ntrip_version',
None)
35 if ntrip_version ==
'':
41 if rospy.get_param(
'~authenticate',
False):
42 username = rospy.get_param(
'~username',
None)
43 password = rospy.get_param(
'~password',
None)
46 'Requested to authenticate, but param "username" was not set')
50 'Requested to authenticate, but param "password" was not set')
57 mountpoint=mountpoint,
58 ntrip_version=ntrip_version,
62 logwarn=rospy.logwarn,
63 loginfo=rospy.loginfo,
64 logdebug=rospy.logdebug
68 self.
_client.ssl = rospy.get_param(
'~ssl',
False)
69 self.
_client.cert = rospy.get_param(
'~cert',
None)
70 self.
_client.key = rospy.get_param(
'~key',
None)
71 self.
_client.ca_cert = rospy.get_param(
'~ca_cert',
None)
78 self.
_client.rtcm_timeout_seconds = rospy.get_param(
'~rtcm_timeout_seconds', NTRIPClient.DEFAULT_RTCM_TIMEOUT_SECONDS)
81 if __name__ ==
'__main__':
83 sys.exit(ntrip_ros.run())