ntrip_serial_device_ros.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 
3 import sys
4 import importlib
5 
6 import rospy
7 
8 from ntrip_client.ntrip_ros_base import NTRIPRosBase
9 from ntrip_client.ntrip_serial_device import NTRIPSerialDevice
10 
11 # Try to import a couple different types of RTCM messages
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:
20  have_rtcm_msgs = True
21  from rtcm_msgs.msg import Message as rtcm_msgs_RTCM
22 
24  def __init__(self):
25  # Init the node
26  super().__init__('ntrip_client')
27 
28  # Read some mandatory config
29  port = rospy.get_param('~port', '/dev/ttyACM0')
30  baudrate = rospy.get_param('~baudrate', 115200)
31 
32  # Initialize the client
34  port=port,
35  baudrate=baudrate,
36  logerr=rospy.logerr,
37  logwarn=rospy.logwarn,
38  loginfo=rospy.loginfo,
39  logdebug=rospy.logdebug
40  )
41 
42  # Set parameters on the client
43  self._client.nmea_parser.nmea_max_length = self._nmea_max_length
44  self._client.nmea_parser.nmea_min_length = self._nmea_min_length
45  self._client.reconnect_attempt_max = self._reconnect_attempt_max
46  self._client.reconnect_attempt_wait_seconds = self._reconnect_attempt_wait_seconds
47 
48 
49 if __name__ == '__main__':
50  ntrip_ros = NTRIPRos()
51  sys.exit(ntrip_ros.run())
ntrip_serial_device_ros.NTRIPRos._client
_client
Definition: ntrip_serial_device_ros.py:33
ntrip_client.ntrip_serial_device
Definition: ntrip_serial_device.py:1
ntrip_client.ntrip_ros_base.NTRIPRosBase
Definition: ntrip_ros_base.py:29
ntrip_client.ntrip_ros_base.NTRIPRosBase._nmea_min_length
_nmea_min_length
Definition: ntrip_ros_base.py:77
ntrip_client.ntrip_serial_device.NTRIPSerialDevice
Definition: ntrip_serial_device.py:9
ntrip_client.ntrip_ros_base.NTRIPRosBase._reconnect_attempt_wait_seconds
_reconnect_attempt_wait_seconds
Definition: ntrip_ros_base.py:79
ntrip_client.ntrip_ros_base.NTRIPRosBase._nmea_max_length
_nmea_max_length
Definition: ntrip_ros_base.py:76
ntrip_serial_device_ros.NTRIPRos.__init__
def __init__(self)
Definition: ntrip_serial_device_ros.py:24
ntrip_client.ntrip_ros_base
Definition: ntrip_ros_base.py:1
ntrip_serial_device_ros.NTRIPRos
Definition: ntrip_serial_device_ros.py:23
ntrip_client.ntrip_ros_base.NTRIPRosBase._reconnect_attempt_max
_reconnect_attempt_max
Definition: ntrip_ros_base.py:78


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