publisher.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 # Software License Agreement (BSD)
00005 #
00006 #  file      @publisher.py
00007 #  authors   Mike Purvis <mpurvis@clearpathrobotics.com>
00008 #            NovAtel <novatel.com/support>
00009 #  copyright Copyright (c) 2012, Clearpath Robotics, Inc., All rights reserved.
00010 #            Copyright (c) 2014, NovAtel Inc., All rights reserved.
00011 #
00012 # Redistribution and use in source and binary forms, with or without modification, are permitted provided that
00013 # the following conditions are met:
00014 #  * Redistributions of source code must retain the above copyright notice, this list of conditions and the
00015 #    following disclaimer.
00016 #  * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
00017 #    following disclaimer in the documentation and/or other materials provided with the distribution.
00018 #  * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
00019 #    products derived from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
00022 # RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
00023 # PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
00024 # DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
00025 # OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 
00029 import rospy
00030 import tf
00031 import geodesy.utm
00032 
00033 from novatel_msgs.msg import BESTPOS, CORRIMUDATA, INSCOV, INSPVAX
00034 from sensor_msgs.msg import Imu, NavSatFix, NavSatStatus
00035 from nav_msgs.msg import Odometry
00036 from geometry_msgs.msg import Quaternion, Point, Pose, Twist
00037 
00038 from math import radians, pow
00039 
00040 # FIXED COVARIANCES
00041 # TODO: Work these out...
00042 IMU_ORIENT_COVAR = [1e-3, 0, 0,
00043                     0, 1e-3, 0,
00044                     0, 0, 1e-3]
00045 
00046 IMU_VEL_COVAR = [1e-3, 0, 0,
00047                  0, 1e-3, 0,
00048                  0, 0, 1e-3]
00049 
00050 IMU_ACCEL_COVAR = [1e-3, 0, 0,
00051                    0, 1e-3, 0,
00052                    0, 0, 1e-3]
00053 
00054 NAVSAT_COVAR = [1, 0, 0,
00055                 0, 1, 0,
00056                 0, 0, 1]
00057 
00058 POSE_COVAR = [1, 0, 0, 0, 0, 0,
00059               0, 1, 0, 0, 0, 0,
00060               0, 0, 1, 0, 0, 0,
00061               0, 0, 0, 0.1, 0, 0,
00062               0, 0, 0, 0, 0.1, 0,
00063               0, 0, 0, 0, 0, 0.1]
00064 
00065 TWIST_COVAR = [1, 0, 0, 0, 0, 0,
00066                0, 1, 0, 0, 0, 0,
00067                0, 0, 1, 0, 0, 0,
00068                0, 0, 0, 0.1, 0, 0,
00069                0, 0, 0, 0, 0.1, 0,
00070                0, 0, 0, 0, 0, 0.1]
00071 
00072 
00073 class NovatelPublisher(object):
00074     """ Subscribes to the directly-translated messages from the SPAN system
00075         and repackages the resultant data as standard ROS messages. """
00076 
00077     def __init__(self):
00078         # Parameters
00079         self.publish_tf = rospy.get_param('~publish_tf', False)
00080         self.odom_frame = rospy.get_param('~odom_frame', 'odom_combined')
00081         self.base_frame = rospy.get_param('~base_frame', 'base_link')
00082 
00083         # When True, UTM odom x, y pose will be published with respect to the
00084         # first coordinate received.
00085         self.zero_start = rospy.get_param('~zero_start', False)
00086 
00087         self.imu_rate = rospy.get_param('~rate', 100)
00088 
00089         # Topic publishers
00090         self.pub_imu = rospy.Publisher('imu/data', Imu, queue_size=1)
00091         self.pub_odom = rospy.Publisher('navsat/odom', Odometry, queue_size=1)
00092         self.pub_origin = rospy.Publisher('navsat/origin', Pose, queue_size=1)
00093         self.pub_navsatfix = rospy.Publisher('navsat/fix', NavSatFix, queue_size=1)
00094 
00095         if self.publish_tf:
00096             self.tf_broadcast = tf.TransformBroadcaster()
00097 
00098         self.init = False       # If we've been initialized
00099         self.origin = Point()   # Where we've started
00100         self.orientation = [0] * 4  # Empty quaternion until we hear otherwise
00101         self.orientation_covariance = IMU_ORIENT_COVAR
00102 
00103         # Subscribed topics
00104         rospy.Subscriber('novatel_data/bestpos', BESTPOS, self.bestpos_handler)
00105         rospy.Subscriber('novatel_data/corrimudata', CORRIMUDATA, self.corrimudata_handler)
00106         rospy.Subscriber('novatel_data/inscov', INSCOV, self.inscov_handler)
00107         rospy.Subscriber('novatel_data/inspvax', INSPVAX, self.inspvax_handler)
00108 
00109     def bestpos_handler(self, bestpos):
00110         navsat = NavSatFix()
00111 
00112         # TODO: The timestamp here should come from SPAN, not the ROS system time.
00113         navsat.header.stamp = rospy.Time.now()
00114         navsat.header.frame_id = self.odom_frame
00115 
00116         # Assume GPS - this isn't exposed
00117         navsat.status.service = NavSatStatus.SERVICE_GPS
00118 
00119         position_type_to_status = {
00120             BESTPOS.POSITION_TYPE_NONE: NavSatStatus.STATUS_NO_FIX,
00121             BESTPOS.POSITION_TYPE_FIXED: NavSatStatus.STATUS_FIX,
00122             BESTPOS.POSITION_TYPE_FIXEDHEIGHT: NavSatStatus.STATUS_FIX,
00123             BESTPOS.POSITION_TYPE_FLOATCONV: NavSatStatus.STATUS_FIX,
00124             BESTPOS.POSITION_TYPE_WIDELANE: NavSatStatus.STATUS_FIX,
00125             BESTPOS.POSITION_TYPE_NARROWLANE: NavSatStatus.STATUS_FIX,
00126             BESTPOS.POSITION_TYPE_DOPPLER_VELOCITY: NavSatStatus.STATUS_FIX,
00127             BESTPOS.POSITION_TYPE_SINGLE: NavSatStatus.STATUS_FIX,
00128             BESTPOS.POSITION_TYPE_PSRDIFF: NavSatStatus.STATUS_GBAS_FIX,
00129             BESTPOS.POSITION_TYPE_WAAS: NavSatStatus.STATUS_GBAS_FIX,
00130             BESTPOS.POSITION_TYPE_PROPAGATED: NavSatStatus.STATUS_GBAS_FIX,
00131             BESTPOS.POSITION_TYPE_OMNISTAR: NavSatStatus.STATUS_SBAS_FIX,
00132             BESTPOS.POSITION_TYPE_L1_FLOAT: NavSatStatus.STATUS_GBAS_FIX,
00133             BESTPOS.POSITION_TYPE_IONOFREE_FLOAT: NavSatStatus.STATUS_GBAS_FIX,
00134             BESTPOS.POSITION_TYPE_NARROW_FLOAT: NavSatStatus.STATUS_GBAS_FIX,
00135             BESTPOS.POSITION_TYPE_L1_INT: NavSatStatus.STATUS_GBAS_FIX,
00136             BESTPOS.POSITION_TYPE_WIDE_INT: NavSatStatus.STATUS_GBAS_FIX,
00137             BESTPOS.POSITION_TYPE_NARROW_INT: NavSatStatus.STATUS_GBAS_FIX,
00138             BESTPOS.POSITION_TYPE_RTK_DIRECT_INS: NavSatStatus.STATUS_GBAS_FIX,
00139             BESTPOS.POSITION_TYPE_INS_SBAS: NavSatStatus.STATUS_SBAS_FIX,
00140             BESTPOS.POSITION_TYPE_INS_PSRSP: NavSatStatus.STATUS_GBAS_FIX,
00141             BESTPOS.POSITION_TYPE_INS_PSRDIFF: NavSatStatus.STATUS_GBAS_FIX,
00142             BESTPOS.POSITION_TYPE_INS_RTKFLOAT: NavSatStatus.STATUS_GBAS_FIX,
00143             BESTPOS.POSITION_TYPE_INS_RTKFIXED: NavSatStatus.STATUS_GBAS_FIX,
00144             BESTPOS.POSITION_TYPE_INS_OMNISTAR: NavSatStatus.STATUS_GBAS_FIX,
00145             BESTPOS.POSITION_TYPE_INS_OMNISTAR_HP: NavSatStatus.STATUS_GBAS_FIX,
00146             BESTPOS.POSITION_TYPE_INS_OMNISTAR_XP: NavSatStatus.STATUS_GBAS_FIX,
00147             BESTPOS.POSITION_TYPE_OMNISTAR_HP: NavSatStatus.STATUS_SBAS_FIX,
00148             BESTPOS.POSITION_TYPE_OMNISTAR_XP: NavSatStatus.STATUS_SBAS_FIX,
00149             BESTPOS.POSITION_TYPE_PPP_CONVERGING: NavSatStatus.STATUS_SBAS_FIX,
00150             BESTPOS.POSITION_TYPE_PPP: NavSatStatus.STATUS_SBAS_FIX,
00151             BESTPOS.POSITION_TYPE_INS_PPP_CONVERGING: NavSatStatus.STATUS_SBAS_FIX,
00152             BESTPOS.POSITION_TYPE_INS_PPP: NavSatStatus.STATUS_SBAS_FIX,
00153             }
00154         navsat.status.status = position_type_to_status.get(bestpos.position_type,
00155                                                            NavSatStatus.STATUS_NO_FIX)
00156 
00157         # Position in degrees.
00158         navsat.latitude = bestpos.latitude
00159         navsat.longitude = bestpos.longitude
00160 
00161         # Altitude in metres.
00162         navsat.altitude = bestpos.altitude
00163         navsat.position_covariance[0] = pow(2, bestpos.latitude_std)
00164         navsat.position_covariance[4] = pow(2, bestpos.longitude_std)
00165         navsat.position_covariance[8] = pow(2, bestpos.altitude_std)
00166         navsat.position_covariance_type = NavSatFix.COVARIANCE_TYPE_DIAGONAL_KNOWN
00167 
00168         # Ship ito
00169         self.pub_navsatfix.publish(navsat)
00170 
00171     def inspvax_handler(self, inspvax):
00172         # Convert the latlong to x,y coordinates and publish an Odometry
00173         try:
00174             utm_pos = geodesy.utm.fromLatLong(inspvax.latitude, inspvax.longitude)
00175         except ValueError:
00176             # Probably coordinates out of range for UTM conversion.
00177             return
00178 
00179         if not self.init and self.zero_start:
00180             self.origin.x = utm_pos.easting
00181             self.origin.y = utm_pos.northing
00182             self.origin.z = inspvax.altitude
00183             self.pub_origin.publish(position=self.origin)
00184 
00185         odom = Odometry()
00186         odom.header.stamp = rospy.Time.now()
00187         odom.header.frame_id = self.odom_frame
00188         odom.child_frame_id = self.base_frame
00189         odom.pose.pose.position.x = utm_pos.easting - self.origin.x
00190         odom.pose.pose.position.y = utm_pos.northing - self.origin.y
00191         odom.pose.pose.position.z = inspvax.altitude - self.origin.z
00192 
00193         # Orientation
00194         # Save this on an instance variable, so that it can be published
00195         # with the IMU message as well.
00196         self.orientation = tf.transformations.quaternion_from_euler(
00197             radians(inspvax.pitch),
00198             radians(inspvax.roll),
00199             radians(90 - inspvax.azimuth))
00200         print inspvax.azimuth
00201         odom.pose.pose.orientation = Quaternion(*self.orientation)
00202         odom.pose.covariance[21] = self.orientation_covariance[0] = pow(2, inspvax.pitch_std)
00203         odom.pose.covariance[28] = self.orientation_covariance[4] = pow(2, inspvax.roll_std)
00204         odom.pose.covariance[35] = self.orientation_covariance[8] = pow(2, inspvax.azimuth_std)
00205 
00206         # Twist is relative to vehicle frame
00207         odom.twist.twist.linear.x = inspvax.east_velocity
00208         odom.twist.twist.linear.y = inspvax.north_velocity
00209         odom.twist.twist.linear.z = inspvax.up_velocity
00210         TWIST_COVAR[0] = pow(2, inspvax.east_velocity_std)
00211         TWIST_COVAR[7] = pow(2, inspvax.north_velocity_std)
00212         TWIST_COVAR[14] = pow(2, inspvax.up_velocity_std)
00213         #odom.twist.twist.angular = imu.angular_velocity
00214         odom.twist.covariance = TWIST_COVAR
00215 
00216         self.pub_odom.publish(odom)
00217 
00218         # Odometry transform (if required)
00219         if self.publish_tf:
00220             self.tf_broadcast.sendTransform(
00221                 (odom.pose.pose.position.x, odom.pose.pose.position.y,
00222                  odom.pose.pose.position.z),
00223                 self.orientation,
00224                 odom.header.stamp, odom.child_frame_id, odom.header.frame_id)
00225 
00226         # Mark that we've received our first fix, and set origin if necessary.
00227         self.init = True
00228 
00229     def corrimudata_handler(self, corrimudata):
00230         # TODO: Work out these covariances properly. Logs provide covariances in local frame, not body
00231         imu = Imu()
00232         imu.header.stamp == rospy.Time.now()
00233         imu.header.frame_id = self.base_frame
00234 
00235         # Populate orientation field with one from inspvax message.
00236         imu.orientation = Quaternion(*self.orientation)
00237         imu.orientation_covariance = self.orientation_covariance
00238 
00239         # Angular rates (rad/s)
00240         # corrimudata log provides instantaneous rates so multiply by IMU rate in Hz
00241         imu.angular_velocity.x = corrimudata.pitch_rate * self.imu_rate
00242         imu.angular_velocity.y = corrimudata.roll_rate * self.imu_rate
00243         imu.angular_velocity.z = corrimudata.yaw_rate * self.imu_rate
00244         imu.angular_velocity_covariance = IMU_VEL_COVAR
00245 
00246         # Linear acceleration (m/s^2)
00247         imu.linear_acceleration.x = corrimudata.x_accel * self.imu_rate
00248         imu.linear_acceleration.y = corrimudata.y_accel * self.imu_rate
00249         imu.linear_acceleration.z = corrimudata.z_accel * self.imu_rate
00250         imu.linear_acceleration_covariance = IMU_ACCEL_COVAR
00251 
00252         self.pub_imu.publish(imu)
00253 
00254     def inscov_handler(self, inscov):
00255         # TODO: Supply this data in the IMU and Odometry messages.
00256         pass


novatel_span_driver
Author(s): NovAtel Support
autogenerated on Fri Aug 28 2015 11:47:11