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
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 import roslib; roslib.load_manifest('applanix_publisher')
00045 import rospy
00046 import tf
00047 import PyKDL
00048
00049
00050 from applanix_msgs.msg import NavigationSolution, GNSSStatus, IMUData
00051 from gps_utm import LLtoUTM
00052
00053
00054 from sensor_msgs.msg import Imu, NavSatFix, NavSatStatus
00055 from nav_msgs.msg import Odometry
00056 from geometry_msgs.msg import Quaternion, Point, Pose
00057
00058
00059 from math import radians as RAD
00060
00061
00062
00063 IMU_ORIENT_COVAR = [1e-3, 0, 0,
00064 0, 1e-3, 0,
00065 0, 0, 1e-3]
00066
00067 IMU_VEL_COVAR = [1e-3, 0, 0,
00068 0, 1e-3, 0,
00069 0, 0, 1e-3]
00070
00071 IMU_ACCEL_COVAR = [1e-3, 0, 0,
00072 0, 1e-3, 0,
00073 0, 0, 1e-3]
00074
00075 NAVSAT_COVAR = [1, 0, 0,
00076 0, 1, 0,
00077 0, 0, 1]
00078
00079 POSE_COVAR = [1, 0, 0, 0, 0, 0,
00080 0, 1, 0, 0, 0, 0,
00081 0, 0, 1, 0, 0, 0,
00082 0, 0, 0, 0.1, 0, 0,
00083 0, 0, 0, 0, 0.1, 0,
00084 0, 0, 0, 0, 0, 0.1]
00085
00086 TWIST_COVAR = [1, 0, 0, 0, 0, 0,
00087 0, 1, 0, 0, 0, 0,
00088 0, 0, 1, 0, 0, 0,
00089 0, 0, 0, 0.1, 0, 0,
00090 0, 0, 0, 0, 0.1, 0,
00091 0, 0, 0, 0, 0, 0.1]
00092
00093 class ApplanixPublisher(object):
00094
00095 def __init__(self):
00096 rospy.init_node('applanix_publisher')
00097
00098 self.publish_tf = rospy.get_param('~publish_tf', False)
00099 self.odom_frame = rospy.get_param('~odom_frame', 'odom_combined')
00100 self.base_frame = rospy.get_param('~base_frame', 'base_footprint')
00101 self.zero_start = rospy.get_param('~zero_start', False)
00102
00103
00104 self.pub_imu = rospy.Publisher('imu_data', Imu)
00105 self.pub_odom = rospy.Publisher('gps_odom', Odometry)
00106 self.pub_origin = rospy.Publisher('origin', Pose)
00107 self.pub_navsatfix = rospy.Publisher('gps_fix', NavSatFix)
00108 self.pub_navsatstatus = rospy.Publisher('gps_status', NavSatStatus)
00109 if self.publish_tf:
00110 self.tf_broadcast = tf.TransfromBroadcaster()
00111
00112
00113 self.nav_status = NavSatStatus()
00114 self.nav_status.status = NavSatStatus.STATUS_NO_FIX
00115 self.nav_status.service = NavSatStatus.SERVICE_GPS
00116
00117 self.init = False
00118 self.origin = Point()
00119
00120
00121 rospy.Subscriber('nav', NavigationSolution, self.navigation_handler)
00122 rospy.Subscriber('status/gnss/primary', GNSSStatus, self.status_handler)
00123
00124 def navigation_handler(self, data):
00125 """ Rebroadcasts navigation data in the following formats:
00126 1) /odom => /base footprint transform (if enabled, as per REP 105)
00127 2) Odometry message, with parent/child IDs as in #1
00128 3) NavSatFix message, for systems which are knowledgeable about GPS stuff
00129 4) IMU messages
00130 """
00131 rospy.logdebug("Navigation received")
00132
00133 if self.nav_status.status == NavSatStatus.STATUS_NO_FIX:
00134 return
00135
00136 orient = PyKDL.Rotation.RPY(RAD(data.roll), RAD(data.pitch), RAD(data.heading)).GetQuaternion()
00137
00138
00139 (zone, easting, northing) = LLtoUTM(23, data.latitude, data.longitude)
00140
00141
00142 if not self.init and self.zero_start:
00143 self.origin.x = easting
00144 self.origin.y = northing
00145 self.init = True
00146
00147
00148 p = Pose()
00149 p.position.x = self.origin.x
00150 p.position.y = self.origin.y
00151 self.pub_origin.publish(p)
00152
00153
00154
00155
00156
00157 odom = Odometry()
00158 odom.header.stamp = rospy.Time.now()
00159 odom.header.frame_id = self.odom_frame
00160 odom.child_frame_id = self.base_frame
00161 odom.pose.pose.position.x = easting - self.origin.x
00162 odom.pose.pose.position.y = northing - self.origin.y
00163 odom.pose.pose.position.z = data.altitude
00164 odom.pose.pose.orientation = Quaternion(*orient)
00165 odom.pose.covariance = POSE_COVAR
00166
00167 odom.twist.twist.linear.x = data.speed
00168 odom.twist.twist.linear.y = 0
00169 odom.twist.twist.linear.z = -data.down_vel
00170 odom.twist.twist.angular.x = RAD(data.ang_rate_long)
00171 odom.twist.twist.angular.y = RAD(-data.ang_rate_trans)
00172 odom.twist.twist.angular.z = RAD(-data.ang_rate_down)
00173 odom.twist.covariance = TWIST_COVAR
00174
00175 self.pub_odom.publish(odom)
00176
00177
00178
00179
00180 if self.publish_tf:
00181 self.tf_broadcast.sendTransform(
00182 (odom.pose.pose.position.x, odom.pose.pose.position.y,
00183 odom.pose.pose.position.z), Quaternion(*orient),
00184 odom.header.stamp,odom.child_frame_id, odom.frame_id)
00185
00186
00187
00188
00189
00190 navsat = NavSatFix()
00191 navsat.header.stamp = rospy.Time.now()
00192 navsat.header.frame_id = self.odom_frame
00193 navsat.status = self.nav_status
00194
00195 navsat.latitude = data.latitude
00196 navsat.longitude = data.longitude
00197 navsat.altitude = data.altitude
00198
00199 navsat.position_covariance = NAVSAT_COVAR
00200 navsat.position_covariance_type = NavSatFix.COVARIANCE_TYPE_UNKNOWN
00201
00202 self.pub_navsatfix.publish(navsat)
00203
00204
00205
00206
00207
00208 imu = Imu()
00209 imu.header.stamp == rospy.Time.now()
00210 imu.header.frame_id = self.base_frame
00211
00212
00213 imu.orientation = Quaternion(*orient)
00214 imu.orientation_covariance = IMU_ORIENT_COVAR
00215
00216
00217 imu.angular_velocity.x = RAD(data.ang_rate_long)
00218 imu.angular_velocity.y = RAD(-data.ang_rate_trans)
00219 imu.angular_velocity.y = RAD(-data.ang_rate_down)
00220 imu.angular_velocity_covariance = IMU_VEL_COVAR
00221
00222
00223 imu.linear_acceleration.x = data.long_accel
00224 imu.linear_acceleration.y = data.trans_accel
00225 imu.linear_acceleration.z = data.down_accel
00226 imu.linear_acceleration_covariance = IMU_ACCEL_COVAR
00227
00228 self.pub_imu.publish(imu)
00229
00230
00231 pass
00232
00233 def status_handler(self, data):
00234 """ Rebroadcasts GNSS status as a standard NavSatStatus message """
00235
00236 solution_map = {
00237 GNSSStatus.SOLUTION_UNKNOWN: NavSatStatus.STATUS_NO_FIX,
00238 GNSSStatus.SOLUTION_NO_DATA: NavSatStatus.STATUS_NO_FIX,
00239 GNSSStatus.SOLUTION_HORIZONTAL_CA: NavSatStatus.STATUS_FIX,
00240 GNSSStatus.SOLUTION_3D_CA: NavSatStatus.STATUS_FIX,
00241 GNSSStatus.SOLUTION_HORIZONTAL_DGPS: NavSatStatus.STATUS_SBAS_FIX,
00242 GNSSStatus.SOLUTION_3D_DGPS: NavSatStatus.STATUS_SBAS_FIX,
00243 GNSSStatus.SOLUTION_FLOAT_RTK: NavSatStatus.STATUS_GBAS_FIX,
00244 GNSSStatus.SOLUTION_WIDE_LANE_RTK: NavSatStatus.STATUS_GBAS_FIX,
00245 GNSSStatus.SOLUTION_NARROW_LANE_RTK: NavSatStatus.STATUS_GBAS_FIX,
00246 GNSSStatus.SOLUTION_P_CODE: NavSatStatus.STATUS_FIX,
00247 GNSSStatus.SOLUTION_OMNISTAR_HP: NavSatStatus.STATUS_SBAS_FIX,
00248 GNSSStatus.SOLUTION_OMNISTAR_XP: NavSatStatus.STATUS_SBAS_FIX,
00249 GNSSStatus.SOLUTION_OMNISTAR_VBS: NavSatStatus.STATUS_SBAS_FIX,
00250 }
00251 self.nav_status.status = solution_map.get(data.solution_status,NavSatStatus.STATUS_NO_FIX)
00252
00253
00254 self.nav_status.service = NavSatStatus.SERVICE_GPS
00255
00256 self.pub_navsatstatus.publish(self.nav_status)
00257
00258
00259 def main():
00260 node = ApplanixPublisher()
00261 rospy.spin()