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 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
00041
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
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
00084
00085 self.zero_start = rospy.get_param('~zero_start', False)
00086
00087 self.imu_rate = rospy.get_param('~rate', 100)
00088
00089
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, latch=True)
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
00099 self.origin = Point()
00100 self.orientation = [0] * 4
00101 self.orientation_covariance = IMU_ORIENT_COVAR
00102
00103
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
00113 navsat.header.stamp = rospy.Time.now()
00114 navsat.header.frame_id = self.odom_frame
00115
00116
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
00158 navsat.latitude = bestpos.latitude
00159 navsat.longitude = bestpos.longitude
00160
00161
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
00169 self.pub_navsatfix.publish(navsat)
00170
00171 def inspvax_handler(self, inspvax):
00172
00173 try:
00174 utm_pos = geodesy.utm.fromLatLong(inspvax.latitude, inspvax.longitude)
00175 except ValueError:
00176
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
00194
00195
00196 self.orientation = tf.transformations.quaternion_from_euler(
00197 radians(inspvax.roll),
00198 radians(inspvax.pitch),
00199 -radians(inspvax.azimuth), 'syxz'))
00200 odom.pose.pose.orientation = Quaternion(*self.orientation)
00201 odom.pose.covariance[21] = self.orientation_covariance[0] = pow(2, inspvax.pitch_std)
00202 odom.pose.covariance[28] = self.orientation_covariance[4] = pow(2, inspvax.roll_std)
00203 odom.pose.covariance[35] = self.orientation_covariance[8] = pow(2, inspvax.azimuth_std)
00204
00205
00206 odom.twist.twist.linear.x = inspvax.east_velocity
00207 odom.twist.twist.linear.y = inspvax.north_velocity
00208 odom.twist.twist.linear.z = inspvax.up_velocity
00209 TWIST_COVAR[0] = pow(2, inspvax.east_velocity_std)
00210 TWIST_COVAR[7] = pow(2, inspvax.north_velocity_std)
00211 TWIST_COVAR[14] = pow(2, inspvax.up_velocity_std)
00212 odom.twist.covariance = TWIST_COVAR
00213
00214 self.pub_odom.publish(odom)
00215
00216
00217 if self.publish_tf:
00218 self.tf_broadcast.sendTransform(
00219 (odom.pose.pose.position.x, odom.pose.pose.position.y,
00220 odom.pose.pose.position.z),
00221 self.orientation,
00222 odom.header.stamp, odom.child_frame_id, odom.header.frame_id)
00223
00224
00225 self.init = True
00226
00227 def corrimudata_handler(self, corrimudata):
00228
00229 imu = Imu()
00230 imu.header.stamp = rospy.Time.now()
00231 imu.header.frame_id = self.base_frame
00232
00233
00234 imu.orientation = Quaternion(*self.orientation)
00235 imu.orientation_covariance = self.orientation_covariance
00236
00237
00238
00239 imu.angular_velocity.x = corrimudata.pitch_rate * self.imu_rate
00240 imu.angular_velocity.y = corrimudata.roll_rate * self.imu_rate
00241 imu.angular_velocity.z = corrimudata.yaw_rate * self.imu_rate
00242 imu.angular_velocity_covariance = IMU_VEL_COVAR
00243
00244
00245 imu.linear_acceleration.x = corrimudata.x_accel * self.imu_rate
00246 imu.linear_acceleration.y = corrimudata.y_accel * self.imu_rate
00247 imu.linear_acceleration.z = corrimudata.z_accel * self.imu_rate
00248 imu.linear_acceleration_covariance = IMU_ACCEL_COVAR
00249
00250 self.pub_imu.publish(imu)
00251
00252 def inscov_handler(self, inscov):
00253
00254 pass