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 class RosNMEADriver(object):
00044 def __init__(self):
00045 self.fix_pub = rospy.Publisher('fix', NavSatFix)
00046 self.vel_pub = rospy.Publisher('vel', TwistStamped)
00047 self.time_ref_pub = rospy.Publisher('time_reference', TimeReference)
00048
00049 self.time_ref_source = rospy.get_param('~time_ref_source',
00050 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" % 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" %
00064 nmea_string)
00065 return False
00066
00067 if timestamp:
00068 current_time = timestamp
00069 else:
00070 current_time = rospy.get_rostime()
00071 current_fix = NavSatFix()
00072 current_fix.header.stamp = current_time
00073 current_fix.header.frame_id = frame_id
00074 current_time_ref = TimeReference()
00075 current_time_ref.header.stamp = current_time
00076 current_time_ref.header.frame_id = frame_id
00077 if self.time_ref_source:
00078 current_time_ref.source = self.time_ref_source
00079 else:
00080 current_time_ref.source = frame_id
00081
00082 if not self.use_RMC and 'GGA' in parsed_sentence:
00083 data = parsed_sentence['GGA']
00084 gps_qual = data['fix_type']
00085 if gps_qual == 0:
00086 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00087 elif gps_qual == 1:
00088 current_fix.status.status = NavSatStatus.STATUS_FIX
00089 elif gps_qual == 2:
00090 current_fix.status.status = NavSatStatus.STATUS_SBAS_FIX
00091 elif gps_qual in (4, 5):
00092 current_fix.status.status = NavSatStatus.STATUS_GBAS_FIX
00093 else:
00094 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00095
00096 current_fix.status.service = NavSatStatus.SERVICE_GPS
00097
00098 current_fix.header.stamp = current_time
00099
00100 latitude = data['latitude']
00101 if data['latitude_direction'] == 'S':
00102 latitude = -latitude
00103 current_fix.latitude = latitude
00104
00105 longitude = data['longitude']
00106 if data['longitude_direction'] == 'W':
00107 longitude = -longitude
00108 current_fix.longitude = longitude
00109
00110 hdop = data['hdop']
00111 current_fix.position_covariance[0] = hdop**2
00112 current_fix.position_covariance[4] = hdop**2
00113 current_fix.position_covariance[8] = (2*hdop)**2
00114 current_fix.position_covariance_type = \
00115 NavSatFix.COVARIANCE_TYPE_APPROXIMATED
00116
00117
00118 altitude = data['altitude'] + data['mean_sea_level']
00119 current_fix.altitude = altitude
00120
00121 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
00122
00123 self.fix_pub.publish(current_fix)
00124 self.time_ref_pub.publish(current_time_ref)
00125
00126 elif 'RMC' in parsed_sentence:
00127 data = parsed_sentence['RMC']
00128
00129
00130 if self.use_RMC:
00131 if data['fix_valid']:
00132 current_fix.status.status = NavSatStatus.STATUS_FIX
00133 else:
00134 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00135
00136 current_fix.status.service = NavSatStatus.SERVICE_GPS
00137
00138 latitude = data['latitude']
00139 if data['latitude_direction'] == 'S':
00140 latitude = -latitude
00141 current_fix.latitude = latitude
00142
00143 longitude = data['longitude']
00144 if data['longitude_direction'] == 'W':
00145 longitude = -longitude
00146 current_fix.longitude = longitude
00147
00148 current_fix.altitude = float('NaN')
00149 current_fix.position_covariance_type = \
00150 NavSatFix.COVARIANCE_TYPE_UNKNOWN
00151
00152 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
00153
00154 self.fix_pub.publish(current_fix)
00155 self.time_ref_pub.publish(current_time_ref)
00156
00157
00158 if data['fix_valid']:
00159 current_vel = TwistStamped()
00160 current_vel.header.stamp = current_time
00161 current_vel.header.frame_id = frame_id
00162 current_vel.twist.linear.x = data['speed'] * \
00163 math.sin(data['true_course'])
00164 current_vel.twist.linear.y = data['speed'] * \
00165 math.cos(data['true_course'])
00166 self.vel_pub.publish(current_vel)
00167 else:
00168 return False
00169
00170 """Helper method for getting the frame_id with the correct TF prefix"""
00171 @staticmethod
00172 def get_frame_id():
00173 frame_id = rospy.get_param('~frame_id', 'gps')
00174 if frame_id[0] != "/":
00175 """Add the TF prefix"""
00176 prefix = ""
00177 prefix_param = rospy.search_param('tf_prefix')
00178 if prefix_param:
00179 prefix = rospy.get_param(prefix_param)
00180 if prefix[0] != "/":
00181 prefix = "/%s" % prefix
00182 return "%s/%s" % (prefix, frame_id)
00183 else:
00184 return frame_id