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 else:
00093 current_fix.status.status = NavSatStatus.STATUS_NO_FIX
00094
00095 current_fix.status.service = NavSatStatus.SERVICE_GPS
00096
00097 current_fix.header.stamp = current_time
00098
00099 latitude = data['latitude']
00100 if data['latitude_direction'] == 'S':
00101 latitude = -latitude
00102 current_fix.latitude = latitude
00103
00104 longitude = data['longitude']
00105 if data['longitude_direction'] == 'W':
00106 longitude = -longitude
00107 current_fix.longitude = longitude
00108
00109 hdop = data['hdop']
00110 current_fix.position_covariance[0] = hdop ** 2
00111 current_fix.position_covariance[4] = hdop ** 2
00112 current_fix.position_covariance[8] = (2 * hdop) ** 2
00113 current_fix.position_covariance_type = \
00114 NavSatFix.COVARIANCE_TYPE_APPROXIMATED
00115
00116
00117 altitude = data['altitude'] + data['mean_sea_level']
00118 current_fix.altitude = altitude
00119
00120 self.fix_pub.publish(current_fix)
00121
00122 if not math.isnan(data['utc_time']):
00123 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
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 self.fix_pub.publish(current_fix)
00153
00154 if not math.isnan(data['utc_time']):
00155 current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time'])
00156 self.time_ref_pub.publish(current_time_ref)
00157
00158
00159 if data['fix_valid']:
00160 current_vel = TwistStamped()
00161 current_vel.header.stamp = current_time
00162 current_vel.header.frame_id = frame_id
00163 current_vel.twist.linear.x = data['speed'] * \
00164 math.sin(data['true_course'])
00165 current_vel.twist.linear.y = data['speed'] * \
00166 math.cos(data['true_course'])
00167 self.vel_pub.publish(current_vel)
00168 else:
00169 return False
00170
00171 """Helper method for getting the frame_id with the correct TF prefix"""
00172
00173 @staticmethod
00174 def get_frame_id():
00175 frame_id = rospy.get_param('~frame_id', 'gps')
00176 if frame_id[0] != "/":
00177 """Add the TF prefix"""
00178 prefix = ""
00179 prefix_param = rospy.search_param('tf_prefix')
00180 if prefix_param:
00181 prefix = rospy.get_param(prefix_param)
00182 if prefix[0] != "/":
00183 prefix = "/%s" % prefix
00184 return "%s/%s" % (prefix, frame_id)
00185 else:
00186 return frame_id