Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import math
00034
00035 import rospy
00036
00037 from sensor_msgs.msg import NavSatFix, NavSatStatus, TimeReference
00038 from geometry_msgs.msg import TwistStamped
00039
00040 from libnmea_navsat_driver.checksum_utils import check_nmea_checksum
00041 import libnmea_navsat_driver.parser
00042
00043
00044 class RosNMEADriver(object):
00045 def __init__(self):
00046 self.fix_pub = rospy.Publisher('fix', NavSatFix, queue_size=1)
00047 self.vel_pub = rospy.Publisher('vel', TwistStamped, queue_size=1)
00048 self.time_ref_pub = rospy.Publisher('time_reference', TimeReference, queue_size=1)
00049
00050 self.time_ref_source = rospy.get_param('~time_ref_source', None)
00051 self.use_RMC = rospy.get_param('~useRMC', False)
00052
00053
00054
00055 def add_sentence(self, nmea_string, frame_id, timestamp=None):
00056 if not check_nmea_checksum(nmea_string):
00057 rospy.logwarn("Received a sentence with an invalid checksum. " +
00058 "Sentence was: %s" % repr(nmea_string))
00059 return False
00060
00061 parsed_sentence = libnmea_navsat_driver.parser.parse_nmea_sentence(nmea_string)
00062 if not parsed_sentence:
00063 rospy.logdebug("Failed to parse NMEA sentence. Sentece was: %s" % nmea_string)
00064 return False
00065
00066 if timestamp:
00067 current_time = timestamp
00068 else:
00069 current_time = rospy.get_rostime()
00070 current_fix = NavSatFix()
00071 current_fix.header.stamp = current_time
00072 current_fix.header.frame_id = frame_id
00073 current_time_ref = TimeReference()
00074 current_time_ref.header.stamp = current_time
00075 current_time_ref.header.frame_id = frame_id
00076 if self.time_ref_source:
00077 current_time_ref.source = self.time_ref_source
00078 else:
00079 current_time_ref.source = frame_id
00080
00081 if not self.use_RMC and 'GGA' in parsed_sentence:
00082 data = parsed_sentence['GGA']
00083 gps_qual = data['fix_type']
00084 if gps_qual == 0:
00085 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00086 elif gps_qual == 1:
00087 current_fix.status.status = NavSatStatus.STATUS_FIX
00088 elif gps_qual == 2:
00089 current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
00090 elif gps_qual in (4, 5):
00091 current_fix.status.status = NavSatStatus.STATUS_GBAS_FIX
00092 elif gps_qual == 9:
00093
00094
00095 current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
00096 else:
00097 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00098
00099 current_fix.status.service = NavSatStatus.SERVICE_GPS
00100
00101 current_fix.header.stamp = current_time
00102
00103 latitude = data['latitude']
00104 if data['latitude_direction'] == 'S':
00105 latitude = -latitude
00106 current_fix.latitude = latitude
00107
00108 longitude = data['longitude']
00109 if data['longitude_direction'] == 'W':
00110 longitude = -longitude
00111 current_fix.longitude = longitude
00112
00113 hdop = data['hdop']
00114 current_fix.position_covariance[0] = hdop ** 2
00115 current_fix.position_covariance[4] = hdop ** 2
00116 current_fix.position_covariance[8] = (2 * hdop) ** 2
00117 current_fix.position_covariance_type = \
00118 NavSatFix.COVARIANCE_TYPE_APPROXIMATED
00119
00120
00121 altitude = data['altitude'] + data['mean_sea_level']
00122 current_fix.altitude = altitude
00123
00124 self.fix_pub.publish(current_fix)
00125
00126 if not math.isnan(data['utc_time']):
00127 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
00128 self.time_ref_pub.publish(current_time_ref)
00129
00130 elif 'RMC' in parsed_sentence:
00131 data = parsed_sentence['RMC']
00132
00133
00134 if self.use_RMC:
00135 if data['fix_valid']:
00136 current_fix.status.status = NavSatStatus.STATUS_FIX
00137 else:
00138 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00139
00140 current_fix.status.service = NavSatStatus.SERVICE_GPS
00141
00142 latitude = data['latitude']
00143 if data['latitude_direction'] == 'S':
00144 latitude = -latitude
00145 current_fix.latitude = latitude
00146
00147 longitude = data['longitude']
00148 if data['longitude_direction'] == 'W':
00149 longitude = -longitude
00150 current_fix.longitude = longitude
00151
00152 current_fix.altitude = float('NaN')
00153 current_fix.position_covariance_type = \
00154 NavSatFix.COVARIANCE_TYPE_UNKNOWN
00155
00156 self.fix_pub.publish(current_fix)
00157
00158 if not math.isnan(data['utc_time']):
00159 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
00160 self.time_ref_pub.publish(current_time_ref)
00161
00162
00163 if data['fix_valid']:
00164 current_vel = TwistStamped()
00165 current_vel.header.stamp = current_time
00166 current_vel.header.frame_id = frame_id
00167 current_vel.twist.linear.x = data['speed'] * \
00168 math.sin(data['true_course'])
00169 current_vel.twist.linear.y = data['speed'] * \
00170 math.cos(data['true_course'])
00171 self.vel_pub.publish(current_vel)
00172 else:
00173 return False
00174
00175 """Helper method for getting the frame_id with the correct TF prefix"""
00176
00177 @staticmethod
00178 def get_frame_id():
00179 frame_id = rospy.get_param('~frame_id', 'gps')
00180 if frame_id[0] != "/":
00181 """Add the TF prefix"""
00182 prefix = ""
00183 prefix_param = rospy.search_param('tf_prefix')
00184 if prefix_param:
00185 prefix = rospy.get_param(prefix_param)
00186 if prefix[0] != "/":
00187 prefix = "/%s" % prefix
00188 return "%s/%s" % (prefix, frame_id)
00189 else:
00190 return frame_id