nmea_serial_driver.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2013, Eric Perko
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the names of the authors nor the names of their
17 # affiliated organizations may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 """Defines the main method for the nmea_serial_driver executable."""
34 
35 import serial
36 import sys
37 
38 import rospy
39 
40 from libnmea_navsat_driver.driver import RosNMEADriver
41 
42 
43 def main():
44  """Create and run the nmea_serial_driver ROS node.
45 
46  Creates a ROS NMEA Driver and feeds it NMEA sentence strings from a serial device.
47 
48  ROS parameters:
49  ~port (str): Path of the serial device to open.
50  ~baud (int): Baud rate to configure the serial device.
51  """
52  rospy.init_node('nmea_serial_driver')
53 
54  serial_port = rospy.get_param('~port', '/dev/ttyUSB0')
55  serial_baud = rospy.get_param('~baud', 4800)
56  frame_id = RosNMEADriver.get_frame_id()
57 
58  try:
59  GPS = serial.Serial(port=serial_port, baudrate=serial_baud, timeout=2)
60 
61  try:
62  driver = RosNMEADriver()
63  while not rospy.is_shutdown():
64  data = GPS.readline().strip()
65  try:
66  driver.add_sentence(data, frame_id)
67  except ValueError as e:
68  rospy.logwarn(
69  "Value error, likely due to missing fields in the NMEA message. "
70  "Error was: %s. Please report this issue at "
71  "github.com/ros-drivers/nmea_navsat_driver, including a bag file with the NMEA "
72  "sentences that caused it." %
73  e)
74 
75  except (rospy.ROSInterruptException, serial.serialutil.SerialException):
76  GPS.close() # Close GPS serial port
77  except serial.SerialException as ex:
78  rospy.logfatal(
79  "Could not open serial port: I/O error({0}): {1}".format(ex.errno, ex.strerror))


nmea_navsat_driver
Author(s): Eric Perko , Steven Martin
autogenerated on Mon Feb 28 2022 22:57:09