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 from rosflight_msgs.msg import GPS
40 
41 from libnmea_navsat_driver.checksum_utils import check_nmea_checksum
43 
44 
45 class RosNMEADriver(object):
46  def __init__(self):
47  self.fix_pub = rospy.Publisher('gps', GPS, queue_size=1)
48  # self.vel_pub = rospy.Publisher('vel', TwistStamped, queue_size=1)
49  self.time_ref_pub = rospy.Publisher('time_reference', TimeReference, queue_size=1)
50 
51  self.time_ref_source = rospy.get_param('~time_ref_source', None)
52  self.use_RMC = rospy.get_param('~useRMC', False)
53 
54  self.speed = 0
55  self.ground_course = 0
56 
57  # Returns True if we successfully did something with the passed in
58  # nmea_string
59  def add_sentence(self, nmea_string, frame_id, timestamp=None):
60  if not check_nmea_checksum(nmea_string):
61  rospy.logwarn("Received a sentence with an invalid checksum. " +
62  "Sentence was: %s" % repr(nmea_string))
63  return False
64 
65  parsed_sentence = libnmea_navsat_driver.parser.parse_nmea_sentence(nmea_string)
66  if not parsed_sentence:
67  rospy.logdebug("Failed to parse NMEA sentence. Sentece was: %s" % nmea_string)
68  return False
69 
70  if timestamp:
71  current_time = timestamp
72  else:
73  current_time = rospy.get_rostime()
74  current_fix = GPS()
75  current_fix.header.stamp = current_time
76  current_fix.header.frame_id = frame_id
77  current_time_ref = TimeReference()
78  current_time_ref.header.stamp = current_time
79  current_time_ref.header.frame_id = frame_id
80  if self.time_ref_source:
81  current_time_ref.source = self.time_ref_source
82  else:
83  current_time_ref.source = frame_id
84 
85  if 'RMC' in parsed_sentence:
86  data = parsed_sentence['RMC']
87  if data['fix_valid']:
88  self.speed = data['speed']
89  if not math.isnan(data['true_course']):
90  self.ground_course = data['true_course']
91 
92  if not self.use_RMC and 'GGA' in parsed_sentence:
93  data = parsed_sentence['GGA']
94  gps_qual = data['fix_type']
95  if gps_qual > 0:
96  current_fix.fix = True
97  current_fix.NumSat = data['num_satellites']
98  # current_fix.status.service = NavSatStatus.SERVICE_GPS
99 
100  current_fix.header.stamp = current_time
101 
102  latitude = data['latitude']
103  if data['latitude_direction'] == 'S':
104  latitude = -latitude
105  current_fix.latitude = latitude
106 
107  longitude = data['longitude']
108  if data['longitude_direction'] == 'W':
109  longitude = -longitude
110  current_fix.longitude = longitude
111 
112  hdop = data['hdop']
113  current_fix.covariance = hdop ** 2
114  # current_fix.position_covariance[4] = hdop ** 2
115  # current_fix.position_covariance[8] = (2 * hdop) ** 2 # FIXME
116  # current_fix.position_covariance_type = \
117  # NavSatFix.COVARIANCE_TYPE_APPROXIMATED
118 
119  # Altitude is above ellipsoid, so adjust for mean-sea-level
120  altitude = data['altitude'] + data['mean_sea_level']
121  current_fix.altitude = altitude
122 
123  current_fix.speed = self.speed
124  current_fix.ground_course = self.ground_course
125 
126  self.fix_pub.publish(current_fix)
127 
128  if not math.isnan(data['utc_time']):
129  current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
130  self.time_ref_pub.publish(current_time_ref)
131 
132  elif 'RMC' in parsed_sentence:
133  data = parsed_sentence['RMC']
134 
135  # Only publish a fix from RMC if the use_RMC flag is set.
136  if self.use_RMC:
137  current_fix.fix = True
138  current_fix.NumSat = data['num_satellites']
139 
140  # current_fix.status.service = NavSatStatus.SERVICE_GPS
141 
142  latitude = data['latitude']
143  if data['latitude_direction'] == 'S':
144  latitude = -latitude
145  current_fix.latitude = latitude
146 
147  longitude = data['longitude']
148  if data['longitude_direction'] == 'W':
149  longitude = -longitude
150  current_fix.longitude = longitude
151 
152  current_fix.altitude = float('NaN')
153 
154  # current_fix.position_covariance_type = \
155  # NavSatFix.COVARIANCE_TYPE_UNKNOWN
156  if data['fix_valid']:
157  current_fix.speed = data['speed']
158  if not math.isnan(data['true_course']):
159  current_fix.ground_course = data['true_course']
160  else:
161  current_fix.ground_course = self.ground_course
162 
163  self.fix_pub.publish(current_fix)
164 
165  if not math.isnan(data['utc_time']):
166  current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
167  self.time_ref_pub.publish(current_time_ref)
168 
169  else:
170  return False
171 
172  """Helper method for getting the frame_id with the correct TF prefix"""
173 
174  @staticmethod
176  frame_id = rospy.get_param('~frame_id', 'gps')
177  if frame_id[0] != "/":
178  """Add the TF prefix"""
179  prefix = ""
180  prefix_param = rospy.search_param('tf_prefix')
181  if prefix_param:
182  prefix = rospy.get_param(prefix_param)
183  if prefix[0] != "/":
184  prefix = "/%s" % prefix
185  return "%s/%s" % (prefix, frame_id)
186  else:
187  return frame_id
def add_sentence(self, nmea_string, frame_id, timestamp=None)
Definition: driver.py:59
def parse_nmea_sentence(nmea_sentence)
Definition: parser.py:127


rosflight_utils
Author(s):
autogenerated on Thu Apr 15 2021 05:10:06