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 import math
34 
35 import rospy
36 
37 from sensor_msgs.msg import NavSatFix, NavSatStatus, TimeReference
38 from geometry_msgs.msg import TwistStamped
39 
40 from libnmea_navsat_driver.checksum_utils import check_nmea_checksum
42 
43 
44 class RosNMEADriver(object):
45  def __init__(self):
46  self.fix_pub = rospy.Publisher('fix', NavSatFix, queue_size=1)
47  self.vel_pub = rospy.Publisher('vel', TwistStamped, queue_size=1)
48  self.time_ref_pub = rospy.Publisher('time_reference', TimeReference, queue_size=1)
49 
50  self.time_ref_source = rospy.get_param('~time_ref_source', None)
51  self.use_RMC = rospy.get_param('~useRMC', False)
52  self.valid_fix = False
53 
54  # Returns True if we successfully did something with the passed in
55  # nmea_string
56  def add_sentence(self, nmea_string, frame_id, timestamp=None):
57  if not check_nmea_checksum(nmea_string):
58  rospy.logwarn("Received a sentence with an invalid checksum. " +
59  "Sentence was: %s" % repr(nmea_string))
60  return False
61 
62  parsed_sentence = libnmea_navsat_driver.parser.parse_nmea_sentence(nmea_string)
63  if not parsed_sentence:
64  rospy.logdebug("Failed to parse NMEA sentence. Sentece was: %s" % nmea_string)
65  return False
66 
67  if timestamp:
68  current_time = timestamp
69  else:
70  current_time = rospy.get_rostime()
71  current_fix = NavSatFix()
72  current_fix.header.stamp = current_time
73  current_fix.header.frame_id = frame_id
74  current_time_ref = TimeReference()
75  current_time_ref.header.stamp = current_time
76  current_time_ref.header.frame_id = frame_id
77  if self.time_ref_source:
78  current_time_ref.source = self.time_ref_source
79  else:
80  current_time_ref.source = frame_id
81 
82  if not self.use_RMC and 'GGA' in parsed_sentence:
83  data = parsed_sentence['GGA']
84  gps_qual = data['fix_type']
85  if gps_qual == 0:
86  current_fix.status.status = NavSatStatus.STATUS_NO_FIX
87  elif gps_qual == 1:
88  current_fix.status.status = NavSatStatus.STATUS_FIX
89  elif gps_qual == 2:
90  current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
91  elif gps_qual in (4, 5):
92  current_fix.status.status = NavSatStatus.STATUS_GBAS_FIX
93  elif gps_qual == 9:
94  # Support specifically for NOVATEL OEM4 recievers which report WAAS fix as 9
95  # http://www.novatel.com/support/known-solutions/which-novatel-position-types-correspond-to-the-gga-quality-indicator/
96  current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
97  else:
98  current_fix.status.status = NavSatStatus.STATUS_NO_FIX
99 
100  if gps_qual > 0:
101  self.valid_fix = True
102  else:
103  self.valid_fix = False
104 
105  current_fix.status.service = NavSatStatus.SERVICE_GPS
106 
107  current_fix.header.stamp = current_time
108 
109  latitude = data['latitude']
110  if data['latitude_direction'] == 'S':
111  latitude = -latitude
112  current_fix.latitude = latitude
113 
114  longitude = data['longitude']
115  if data['longitude_direction'] == 'W':
116  longitude = -longitude
117  current_fix.longitude = longitude
118 
119  hdop = data['hdop']
120  current_fix.position_covariance[0] = hdop ** 2
121  current_fix.position_covariance[4] = hdop ** 2
122  current_fix.position_covariance[8] = (2 * hdop) ** 2 # FIXME
123  current_fix.position_covariance_type = \
124  NavSatFix.COVARIANCE_TYPE_APPROXIMATED
125 
126  # Altitude is above ellipsoid, so adjust for mean-sea-level
127  altitude = data['altitude'] + data['mean_sea_level']
128  current_fix.altitude = altitude
129 
130  self.fix_pub.publish(current_fix)
131 
132  if not math.isnan(data['utc_time']):
133  current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
134  self.last_valid_fix_time = current_time_ref
135  self.time_ref_pub.publish(current_time_ref)
136 
137  elif not self.use_RMC and 'VTG' in parsed_sentence:
138  data = parsed_sentence['VTG']
139 
140  # Only report VTG data when you've received a valid GGA fix as well.
141  if self.valid_fix:
142  current_vel = TwistStamped()
143  current_vel.header.stamp = current_time
144  current_vel.header.frame_id = frame_id
145  current_vel.twist.linear.x = data['speed'] * \
146  math.sin(data['true_course'])
147  current_vel.twist.linear.y = data['speed'] * \
148  math.cos(data['true_course'])
149  self.vel_pub.publish(current_vel)
150 
151  elif 'RMC' in parsed_sentence:
152  data = parsed_sentence['RMC']
153 
154  # Only publish a fix from RMC if the use_RMC flag is set.
155  if self.use_RMC:
156  if data['fix_valid']:
157  current_fix.status.status = NavSatStatus.STATUS_FIX
158  else:
159  current_fix.status.status = NavSatStatus.STATUS_NO_FIX
160 
161  current_fix.status.service = NavSatStatus.SERVICE_GPS
162 
163  latitude = data['latitude']
164  if data['latitude_direction'] == 'S':
165  latitude = -latitude
166  current_fix.latitude = latitude
167 
168  longitude = data['longitude']
169  if data['longitude_direction'] == 'W':
170  longitude = -longitude
171  current_fix.longitude = longitude
172 
173  current_fix.altitude = float('NaN')
174  current_fix.position_covariance_type = \
175  NavSatFix.COVARIANCE_TYPE_UNKNOWN
176 
177  self.fix_pub.publish(current_fix)
178 
179  if not math.isnan(data['utc_time']):
180  current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
181  self.time_ref_pub.publish(current_time_ref)
182 
183  # Publish velocity from RMC regardless, since GGA doesn't provide it.
184  if data['fix_valid']:
185  current_vel = TwistStamped()
186  current_vel.header.stamp = current_time
187  current_vel.header.frame_id = frame_id
188  current_vel.twist.linear.x = data['speed'] * \
189  math.sin(data['true_course'])
190  current_vel.twist.linear.y = data['speed'] * \
191  math.cos(data['true_course'])
192  self.vel_pub.publish(current_vel)
193  else:
194  return False
195 
196  """Helper method for getting the frame_id with the correct TF prefix"""
197 
198  @staticmethod
200  frame_id = rospy.get_param('~frame_id', 'gps')
201  if frame_id[0] != "/":
202  """Add the TF prefix"""
203  prefix = ""
204  prefix_param = rospy.search_param('tf_prefix')
205  if prefix_param:
206  prefix = rospy.get_param(prefix_param)
207  if prefix[0] != "/":
208  prefix = "/%s" % prefix
209  return "%s/%s" % (prefix, frame_id)
210  else:
211  return frame_id
def add_sentence(self, nmea_string, frame_id, timestamp=None)
Definition: driver.py:56
def parse_nmea_sentence(nmea_sentence)
Definition: parser.py:144


nmea_navsat_driver
Author(s): Eric Perko , Steven Martin
autogenerated on Mon Jun 10 2019 13:59:05