nmea_gps_driver.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2012, Steven Martin, Eric Perko
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the names of the authors nor the names of their
00019 #    affiliated organizations may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 import rospy
00036 from sensor_msgs.msg import NavSatFix
00037 from sensor_msgs.msg import NavSatStatus
00038 from sensor_msgs.msg import TimeReference
00039 from geometry_msgs.msg import TwistStamped
00040 
00041 from libnmea_navsat_driver.checksum_utils import check_nmea_checksum
00042 import libnmea_navsat_driver.parser
00043 
00044 import serial, string, math, time, calendar
00045 
00046 #nmea_utc should be a string of form hhmmss
00047 def convertNMEATimeToROS(nmea_utc):
00048     #Get current time in UTC for date information
00049     utc_struct = time.gmtime() #immutable, so cannot modify this one
00050     utc_list = list(utc_struct)
00051     hours = int(nmea_utc[0:2])
00052     minutes = int(nmea_utc[2:4])
00053     seconds = int(nmea_utc[4:6])
00054     utc_list[3] = hours
00055     utc_list[4] = minutes
00056     utc_list[5] = seconds
00057     unix_time = calendar.timegm(tuple(utc_list))
00058     return rospy.Time.from_sec(unix_time)
00059 
00060 #Add the tf_prefix to the given frame id
00061 def addTFPrefix(frame_id):
00062     prefix = ""
00063     prefix_param = rospy.search_param("tf_prefix")
00064     if prefix_param:
00065         prefix = rospy.get_param(prefix_param)
00066         if prefix[0] != "/":
00067             prefix = "/%s" % prefix
00068 
00069     return "%s/%s" % (prefix, frame_id)
00070 
00071 if __name__ == "__main__":
00072     #init publisher
00073     rospy.init_node('nmea_gps_driver')
00074     rospy.logwarn("nmea_gps_driver.py is deprecated and planned for removal in I-Turtle. Use 'rosrun nmea_navsat_driver nmea_serial_driver' instead. See ros.org/wiki/nmea_gps_driver for more details.")
00075     gpspub = rospy.Publisher('fix', NavSatFix)
00076     gpsVelPub = rospy.Publisher('vel',TwistStamped)
00077     gpstimePub = rospy.Publisher('time_reference', TimeReference)
00078     #Init GPS port
00079     GPSport = rospy.get_param('~port','/dev/ttyUSB0')
00080     GPSrate = rospy.get_param('~baud',4800)
00081     frame_id = rospy.get_param('~frame_id','gps')
00082     if frame_id[0] != "/":
00083         frame_id = addTFPrefix(frame_id)
00084 
00085     time_ref_source = rospy.get_param('~time_ref_source', frame_id)
00086     useRMC = rospy.get_param('~useRMC', False)
00087     #useRMC == True -> generate info from RMC+GSA
00088     #useRMC == False -> generate info from GGA
00089     navData = NavSatFix()
00090     gpsVel = TwistStamped()
00091     gpstime = TimeReference()
00092     gpstime.source = time_ref_source
00093     navData.header.frame_id = frame_id
00094     gpsVel.header.frame_id = frame_id
00095     GPSLock = False
00096     try:
00097         GPS = serial.Serial(port=GPSport, baudrate=GPSrate, timeout=2)
00098         #Read in GPS
00099         while not rospy.is_shutdown():
00100             #read GPS line
00101             data = GPS.readline().strip()
00102 
00103             if not check_nmea_checksum(data):
00104                 rospy.logwarn("Received a sentence with an invalid checksum. Sentence was: %s" % data)
00105                 continue
00106 
00107             timeNow = rospy.get_rostime()
00108             fields = data.split(',')
00109             for i in fields:
00110                 i = i.strip(',')
00111             try:
00112                 if useRMC:
00113                     #Check for satellite lock
00114                     if 'GSA' in fields[0]:
00115                         lockState = int(fields[2])
00116                         #print 'lockState=',lockState
00117                         if lockState == 3:
00118                             GPSLock = True
00119                         else:
00120                             GPSLock = False
00121                     #if not satellite lock message parse it separately
00122                     else:
00123                         if GPSLock == True:
00124                             if 'RMC' in fields[0]:
00125                                 #print fields
00126                                 gpsVel.header.stamp = timeNow
00127                                 gpsVel.twist.linear.x = float(fields[7])*0.514444444444*math.sin(float(fields[8]))
00128                                 gpsVel.twist.linear.y = float(fields[7])*0.514444444444*math.cos(float(fields[8]))
00129                                 gpsVelPub.publish(gpsVel)
00130 
00131                                 navData.status.status = NavSatStatus.STATUS_FIX
00132                                 navData.header.stamp = gpsVel.header.stamp
00133                                 navData.status.service = NavSatStatus.SERVICE_GPS
00134 
00135                                 gpstime.header.stamp = gpsVel.header.stamp
00136                                 gpstime.time_ref = convertNMEATimeToROS(fields[1])
00137 
00138                                 longitude = float(fields[5][0:3]) + float(fields[5][3:])/60
00139                                 if fields[6] == 'W':
00140                                     longitude = -longitude
00141 
00142                                 latitude = float(fields[3][0:2]) + float(fields[3][2:])/60
00143                                 if fields[4] == 'S':
00144                                     latitude = -latitude
00145 
00146                                 #publish data
00147                                 navData.latitude = latitude
00148                                 navData.longitude = longitude
00149                                 navData.altitude = float('NaN')
00150                                 navData.position_covariance_type = NavSatFix.COVARIANCE_TYPE_UNKNOWN
00151                                 gpspub.publish(navData)
00152                                 gpstimePub.publish(gpstime)
00153                         else:
00154                             pass
00155                             #print data
00156                 else:
00157                     #print "Parsing NMEA sentence"
00158                     #print data
00159                     sentence = libnmea_navsat_driver.parser.parse_nmea_sentence(data)
00160                     #print "Parsed NMEA sentence"
00161                     #print sentence
00162                     if not sentence:
00163                         continue
00164                     #Use GGA
00165                     #No /vel output from just GGA
00166                     if 'GGA' in sentence:
00167                         data_map = sentence["GGA"]
00168                         gps_quality = data_map['fix_type']
00169                         if gps_quality == 0:
00170                             navData.status.status = NavSatStatus.STATUS_NO_FIX
00171                         elif gps_quality == 1:
00172                             navData.status.status = NavSatStatus.STATUS_FIX
00173                         elif gps_quality == 2:
00174                             navData.status.status = NavSatStatus.STATUS_SBAS_FIX
00175                         elif gps_quality in (4,5):
00176                             #Maybe 2 should also sometimes be GBAS... but pretty
00177                             #sure RTK has to have a base station
00178                             navData.status.status = NavSatStatus.STATUS_GBAS_FIX
00179                         else:
00180                             navData.status.status = NavSatStatus.STATUS_NO_FIX
00181                         navData.status.service = NavSatStatus.SERVICE_GPS
00182 
00183                         navData.header.stamp = timeNow
00184 
00185                         latitude = data_map["latitude"]
00186                         if data_map["latitude_direction"] == 'S':
00187                             latitude = -latitude
00188                         navData.latitude = latitude
00189 
00190                         longitude = data_map["longitude"]
00191                         if data_map["longitude_direction"] == 'W':
00192                             longitude = -longitude
00193                         navData.longitude = longitude
00194 
00195                         hdop = data_map["hdop"]
00196                         navData.position_covariance[0] = hdop**2
00197                         navData.position_covariance[4] = hdop**2
00198                         navData.position_covariance[8] = (2*hdop)**2 #FIX ME
00199                         navData.position_covariance_type = NavSatFix.COVARIANCE_TYPE_APPROXIMATED
00200 
00201                         #Altitude is above ellipsoid, so adjust for mean-sea-level
00202                         altitude = data_map["altitude"] + data_map["mean_sea_level"]
00203                         navData.altitude = altitude
00204 
00205                         gpstime.header.stamp = timeNow
00206                         gpstime.time_ref = rospy.Time.from_sec(data_map["utc_time"])
00207 
00208                         gpspub.publish(navData)
00209                         gpstimePub.publish(gpstime)
00210             except ValueError as e:
00211                 rospy.logwarn("Value error, likely due to missing fields in the NMEA messages. Error was: %s" % e)
00212 
00213     except rospy.ROSInterruptException:
00214         GPS.close() #Close GPS serial port


nmea_gps_driver
Author(s): Eric Perko , Steven Martin
autogenerated on Thu Aug 27 2015 14:10:34