37 from sensor_msgs.msg
import NavSatFix, NavSatStatus, TimeReference
38 from geometry_msgs.msg
import TwistStamped
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)
51 self.
use_RMC = rospy.get_param(
'~useRMC',
False)
58 rospy.logwarn(
"Received a sentence with an invalid checksum. " +
59 "Sentence was: %s" % repr(nmea_string))
63 if not parsed_sentence:
64 rospy.logdebug(
"Failed to parse NMEA sentence. Sentece was: %s" % nmea_string)
68 current_time = timestamp
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
80 current_time_ref.source = frame_id
82 if not self.
use_RMC and 'GGA' in parsed_sentence:
83 data = parsed_sentence[
'GGA']
84 gps_qual = data[
'fix_type']
86 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
88 current_fix.status.status = NavSatStatus.STATUS_FIX
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
96 current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
98 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
105 current_fix.status.service = NavSatStatus.SERVICE_GPS
107 current_fix.header.stamp = current_time
109 latitude = data[
'latitude']
110 if data[
'latitude_direction'] ==
'S':
112 current_fix.latitude = latitude
114 longitude = data[
'longitude']
115 if data[
'longitude_direction'] ==
'W':
116 longitude = -longitude
117 current_fix.longitude = longitude
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
123 current_fix.position_covariance_type = \
124 NavSatFix.COVARIANCE_TYPE_APPROXIMATED
127 altitude = data[
'altitude'] + data[
'mean_sea_level']
128 current_fix.altitude = altitude
130 self.fix_pub.publish(current_fix)
132 if not math.isnan(data[
'utc_time']):
133 current_time_ref.time_ref = rospy.Time.from_sec(data[
'utc_time'])
135 self.time_ref_pub.publish(current_time_ref)
137 elif not self.
use_RMC and 'VTG' in parsed_sentence:
138 data = parsed_sentence[
'VTG']
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)
151 elif 'RMC' in parsed_sentence:
152 data = parsed_sentence[
'RMC']
156 if data[
'fix_valid']:
157 current_fix.status.status = NavSatStatus.STATUS_FIX
159 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
161 current_fix.status.service = NavSatStatus.SERVICE_GPS
163 latitude = data[
'latitude']
164 if data[
'latitude_direction'] ==
'S':
166 current_fix.latitude = latitude
168 longitude = data[
'longitude']
169 if data[
'longitude_direction'] ==
'W':
170 longitude = -longitude
171 current_fix.longitude = longitude
173 current_fix.altitude = float(
'NaN')
174 current_fix.position_covariance_type = \
175 NavSatFix.COVARIANCE_TYPE_UNKNOWN
177 self.fix_pub.publish(current_fix)
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)
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)
196 """Helper method for getting the frame_id with the correct TF prefix""" 200 frame_id = rospy.get_param(
'~frame_id',
'gps')
201 if frame_id[0] !=
"/":
202 """Add the TF prefix""" 204 prefix_param = rospy.search_param(
'tf_prefix')
206 prefix = rospy.get_param(prefix_param)
208 prefix =
"/%s" % prefix
209 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)