nmea_topic_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_topic_driver executable."""
34 
35 
36 from nmea_msgs.msg import Sentence
37 import rospy
38 
39 from libnmea_navsat_driver.driver import RosNMEADriver
40 
41 
42 def nmea_sentence_callback(nmea_sentence, driver):
43  """Process a NMEA sentence message with a RosNMEADriver.
44 
45  Args:
46  nmea_sentence (nmea_msgs.msg.Sentence): NMEA sentence message to feed to the driver.
47  driver (RosNMEADriver): Driver to feed the sentence.
48  """
49  try:
50  driver.add_sentence(
51  nmea_sentence.sentence,
52  frame_id=nmea_sentence.header.frame_id,
53  timestamp=nmea_sentence.header.stamp)
54  except ValueError as e:
55  rospy.logwarn(
56  "Value error, likely due to missing fields in the NMEA message. "
57  "Error was: %s. Please report this issue at github.com/ros-drivers/nmea_navsat_driver, "
58  "including a bag file with the NMEA sentences that caused it." %
59  e)
60 
61 
62 def main():
63  """Create and run the nmea_topic_driver ROS node.
64 
65  Creates a NMEA Driver and feeds it NMEA sentence strings from a ROS subscriber.
66 
67  ROS subscribers:
68  mea_sentence (nmea_msgs.msg.Sentence): NMEA sentence messages to feed to the driver.
69  """
70  rospy.init_node('nmea_topic_driver')
71 
72  driver = RosNMEADriver()
73 
74  rospy.Subscriber("nmea_sentence", Sentence, nmea_sentence_callback,
75  driver)
76 
77  rospy.spin()
def nmea_sentence_callback(nmea_sentence, driver)


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