37 from sensor_msgs.msg
import NavSatFix, NavSatStatus, TimeReference
38 from geometry_msgs.msg
import TwistStamped
39 from rosflight_msgs.msg
import GPS
47 self.
fix_pub = rospy.Publisher(
'gps', GPS, queue_size=1)
49 self.
time_ref_pub = rospy.Publisher(
'time_reference', TimeReference, queue_size=1)
52 self.
use_RMC = rospy.get_param(
'~useRMC',
False)
61 rospy.logwarn(
"Received a sentence with an invalid checksum. " +
62 "Sentence was: %s" % repr(nmea_string))
66 if not parsed_sentence:
67 rospy.logdebug(
"Failed to parse NMEA sentence. Sentece was: %s" % nmea_string)
71 current_time = timestamp
73 current_time = rospy.get_rostime()
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
83 current_time_ref.source = frame_id
85 if 'RMC' in parsed_sentence:
86 data = parsed_sentence[
'RMC']
88 self.
speed = data[
'speed']
89 if not math.isnan(data[
'true_course']):
92 if not self.
use_RMC and 'GGA' in parsed_sentence:
93 data = parsed_sentence[
'GGA']
94 gps_qual = data[
'fix_type']
96 current_fix.fix =
True 97 current_fix.NumSat = data[
'num_satellites']
100 current_fix.header.stamp = current_time
102 latitude = data[
'latitude']
103 if data[
'latitude_direction'] ==
'S':
105 current_fix.latitude = latitude
107 longitude = data[
'longitude']
108 if data[
'longitude_direction'] ==
'W':
109 longitude = -longitude
110 current_fix.longitude = longitude
113 current_fix.covariance = hdop ** 2
120 altitude = data[
'altitude'] + data[
'mean_sea_level']
121 current_fix.altitude = altitude
123 current_fix.speed = self.
speed 126 self.fix_pub.publish(current_fix)
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)
132 elif 'RMC' in parsed_sentence:
133 data = parsed_sentence[
'RMC']
137 current_fix.fix =
True 138 current_fix.NumSat = data[
'num_satellites']
142 latitude = data[
'latitude']
143 if data[
'latitude_direction'] ==
'S':
145 current_fix.latitude = latitude
147 longitude = data[
'longitude']
148 if data[
'longitude_direction'] ==
'W':
149 longitude = -longitude
150 current_fix.longitude = longitude
152 current_fix.altitude = float(
'NaN')
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']
163 self.fix_pub.publish(current_fix)
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)
172 """Helper method for getting the frame_id with the correct TF prefix""" 176 frame_id = rospy.get_param(
'~frame_id',
'gps')
177 if frame_id[0] !=
"/":
178 """Add the TF prefix""" 180 prefix_param = rospy.search_param(
'tf_prefix')
182 prefix = rospy.get_param(prefix_param)
184 prefix =
"/%s" % prefix
185 return "%s/%s" % (prefix, frame_id)
def add_sentence(self, nmea_string, frame_id, timestamp=None)
def parse_nmea_sentence(nmea_sentence)
def check_nmea_checksum(nmea_sentence)