00001
00002 import roslib; roslib.load_manifest('xsens_driver')
00003 import rospy
00004 import select
00005
00006 import mtdevice
00007 import mtdef
00008
00009 from std_msgs.msg import Header, String, UInt16
00010 from sensor_msgs.msg import Imu, NavSatFix, NavSatStatus, MagneticField,\
00011 FluidPressure, Temperature, TimeReference
00012 from geometry_msgs.msg import TwistStamped, PointStamped
00013 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00014 import time
00015 import datetime
00016
00017
00018 from math import radians, sqrt, atan2
00019 from tf.transformations import quaternion_from_matrix, quaternion_from_euler,\
00020 identity_matrix
00021
00022
00023 def get_param(name, default):
00024 try:
00025 v = rospy.get_param(name)
00026 rospy.loginfo("Found parameter: %s, value: %s" % (name, str(v)))
00027 except KeyError:
00028 v = default
00029 rospy.logwarn("Cannot find value for parameter: %s, assigning "
00030 "default: %s" % (name, str(v)))
00031 return v
00032
00033
00034 class XSensDriver(object):
00035
00036 def __init__(self):
00037
00038 device = get_param('~device', 'auto')
00039 baudrate = get_param('~baudrate', 0)
00040 timeout = get_param('~timeout', 0.002)
00041 if device == 'auto':
00042 devs = mtdevice.find_devices()
00043 if devs:
00044 device, baudrate = devs[0]
00045 rospy.loginfo("Detected MT device on port %s @ %d bps"
00046 % (device, baudrate))
00047 else:
00048 rospy.logerr("Fatal: could not find proper MT device.")
00049 rospy.signal_shutdown("Could not find proper MT device.")
00050 return
00051 if not baudrate:
00052 baudrate = mtdevice.find_baudrate(device)
00053 if not baudrate:
00054 rospy.logerr("Fatal: could not find proper baudrate.")
00055 rospy.signal_shutdown("Could not find proper baudrate.")
00056 return
00057
00058 rospy.loginfo("MT node interface: %s at %d bd." % (device, baudrate))
00059 self.mt = mtdevice.MTDevice(device, baudrate, timeout)
00060
00061
00062
00063 no_rotation_duration = get_param('~no_rotation_duration', 0)
00064 if no_rotation_duration:
00065 rospy.loginfo("Starting the no-rotation procedure to estimate the "
00066 "gyroscope biases for %d s. Please don't move the IMU"
00067 " during this time." % no_rotation_duration)
00068 self.mt.SetNoRotation(no_rotation_duration)
00069
00070 self.frame_id = get_param('~frame_id', '/base_imu')
00071
00072 self.frame_local = get_param('~frame_local', 'ENU')
00073
00074 self.diag_msg = DiagnosticArray()
00075 self.stest_stat = DiagnosticStatus(name='mtnode: Self Test', level=1,
00076 message='No status information')
00077 self.xkf_stat = DiagnosticStatus(name='mtnode: XKF Valid', level=1,
00078 message='No status information')
00079 self.gps_stat = DiagnosticStatus(name='mtnode: GPS Fix', level=1,
00080 message='No status information')
00081 self.diag_msg.status = [self.stest_stat, self.xkf_stat, self.gps_stat]
00082
00083
00084 self.diag_pub = None
00085 self.imu_pub = None
00086 self.gps_pub = None
00087 self.vel_pub = None
00088 self.mag_pub = None
00089 self.temp_pub = None
00090 self.press_pub = None
00091 self.analog_in1_pub = None
00092 self.analog_in2_pub = None
00093 self.ecef_pub = None
00094 self.time_ref_pub = None
00095
00096 self.old_bGPS = 256
00097
00098
00099 self.str_pub = rospy.Publisher('imu_data_str', String, queue_size=10)
00100 self.last_delta_q_time = None
00101 self.delta_q_rate = None
00102
00103 def reset_vars(self):
00104 self.imu_msg = Imu()
00105 self.imu_msg.orientation_covariance = (-1., )*9
00106 self.imu_msg.angular_velocity_covariance = (-1., )*9
00107 self.imu_msg.linear_acceleration_covariance = (-1., )*9
00108 self.pub_imu = False
00109 self.gps_msg = NavSatFix()
00110 self.pub_gps = False
00111 self.vel_msg = TwistStamped()
00112 self.pub_vel = False
00113 self.mag_msg = MagneticField()
00114 self.mag_msg.magnetic_field_covariance = (0, )*9
00115 self.pub_mag = False
00116 self.temp_msg = Temperature()
00117 self.temp_msg.variance = 0.
00118 self.pub_temp = False
00119 self.press_msg = FluidPressure()
00120 self.press_msg.variance = 0.
00121 self.pub_press = False
00122 self.anin1_msg = UInt16()
00123 self.pub_anin1 = False
00124 self.anin2_msg = UInt16()
00125 self.pub_anin2 = False
00126 self.ecef_msg = PointStamped()
00127 self.pub_ecef = False
00128 self.pub_diag = False
00129
00130 def spin(self):
00131 try:
00132 while not rospy.is_shutdown():
00133 self.spin_once()
00134 self.reset_vars()
00135
00136
00137 except select.error:
00138 pass
00139
00140 def spin_once(self):
00141 '''Read data from device and publishes ROS messages.'''
00142 def convert_coords(x, y, z, source, dest=self.frame_local):
00143 """Convert the coordinates between ENU, NED, and NWU."""
00144 if source == dest:
00145 return x, y, z
00146
00147 if source == 'NED':
00148 x, y, z = y, x, -z
00149 elif source == 'NWU':
00150 x, y, z = -y, x, z
00151
00152 if dest == 'NED':
00153 x, y, z = y, x, -z
00154 elif dest == 'NWU':
00155 x, y, z = y, -x, z
00156 return x, y, z
00157
00158 def convert_quat(q, source, dest=self.frame_local):
00159 """Convert a quaternion between ENU, NED, and NWU."""
00160 def q_mult((w0, x0, y0, z0), (w1, x1, y1, z1)):
00161 """Quaternion multiplication."""
00162 w = w0*w1 - x0*x1 - y0*y1 - z0*z1
00163 x = w0*x1 + x0*w1 + y0*z1 - z0*y1
00164 y = w0*y1 - x0*z1 + y0*w1 + z0*x1
00165 z = w0*z1 + x0*y1 - y0*x1 + z0*w1
00166 return (w, x, y, z)
00167 q_enu_ned = (0, 1./sqrt(2), 1./sqrt(2), 0)
00168 q_enu_nwu = (1./sqrt(2), 0, 0, -1./sqrt(2))
00169 q_ned_nwu = (0, -1, 0, 0)
00170 q_ned_enu = (0, -1./sqrt(2), -1./sqrt(2), 0)
00171 q_nwu_enu = (1./sqrt(2), 0, 0, 1./sqrt(2))
00172 q_nwu_ned = (0, 1, 0, 0)
00173 if source == 'ENU':
00174 if dest == 'ENU':
00175 return q
00176 elif dest == 'NED':
00177 return q_mult(q_enu_ned, q)
00178 elif dest == 'NWU':
00179 return q_mult(q_enu_nwu, q)
00180 elif source == 'NED':
00181 if dest == 'ENU':
00182 return q_mult(q_ned_enu, q)
00183 elif dest == 'NED':
00184 return q
00185 elif dest == 'NWU':
00186 return q_mult(q_ned_nwu, q)
00187 elif source == 'NWU':
00188 if dest == 'ENU':
00189 return q_mult(q_nwu_enu, q)
00190 elif dest == 'NED':
00191 return q_mult(q_nwu_ned, q)
00192 elif dest == 'NWU':
00193 return q
00194
00195 def publish_time_ref(secs, nsecs, source):
00196 """Publish a time reference."""
00197
00198
00199 if self.time_ref_pub is None:
00200 self.time_ref_pub = rospy.Publisher(
00201 'time_reference', TimeReference, queue_size=10)
00202 time_ref_msg = TimeReference()
00203 time_ref_msg.header = self.h
00204 time_ref_msg.time_ref.secs = secs
00205 time_ref_msg.time_ref.nsecs = nsecs
00206 time_ref_msg.source = source
00207 self.time_ref_pub.publish(time_ref_msg)
00208
00209 def stamp_from_itow(itow, y=None, m=None, d=None, ns=0, week=None):
00210 """Return (secs, nsecs) from GPS time of week ms information."""
00211 if y is not None:
00212 stamp_day = datetime.datetime(y, m, d)
00213 elif week is not None:
00214 epoch = datetime.datetime(1980, 1, 6)
00215 stamp_day = epoch + datetime.timedelta(weeks=week)
00216 else:
00217 today = datetime.date.today()
00218 stamp_day = datetime.datetime(today.year, today.month,
00219 today.day)
00220 iso_day = stamp_day.isoweekday()
00221
00222 start_of_week = stamp_day - datetime.timedelta(days=iso_day)
00223
00224 stamp_ms = start_of_week + datetime.timedelta(milliseconds=itow)
00225 secs = time.mktime((stamp_ms.year, stamp_ms.month, stamp_ms.day,
00226 stamp_ms.hour, stamp_ms.minute,
00227 stamp_ms.second, 0, 0, -1))
00228 nsecs = stamp_ms.microsecond * 1000 + ns
00229 if nsecs < 0:
00230 secs -= 1
00231 nsecs += 1e9
00232 return (secs, nsecs)
00233
00234
00235 def fill_from_RAW(raw_data):
00236 '''Fill messages with information from 'raw' MTData block.'''
00237
00238
00239 rospy.loginfo("Got MTi data packet: 'RAW', ignored!")
00240
00241 def fill_from_RAWGPS(rawgps_data):
00242 '''Fill messages with information from 'rawgps' MTData block.'''
00243 if rawgps_data['bGPS'] < self.old_bGPS:
00244 self.pub_gps = True
00245
00246 self.gps_msg.latitude = rawgps_data['LAT']*1e-7
00247 self.gps_msg.longitude = rawgps_data['LON']*1e-7
00248 self.gps_msg.altitude = rawgps_data['ALT']*1e-3
00249
00250 self.old_bGPS = rawgps_data['bGPS']
00251
00252 def fill_from_Temp(temp):
00253 '''Fill messages with information from 'temperature' MTData block.
00254 '''
00255 self.pub_temp = True
00256 self.temp_msg.temperature = temp
00257
00258 def fill_from_Calib(imu_data):
00259 '''Fill messages with information from 'calibrated' MTData block.'''
00260 try:
00261 self.pub_imu = True
00262 x, y, z = convert_coords(imu_data['gyrX'], imu_data['gyrY'],
00263 imu_data['gyrZ'], o['frame'])
00264 self.imu_msg.angular_velocity.x = x
00265 self.imu_msg.angular_velocity.y = y
00266 self.imu_msg.angular_velocity.z = z
00267 self.imu_msg.angular_velocity_covariance = (
00268 radians(0.025), 0., 0.,
00269 0., radians(0.025), 0.,
00270 0., 0., radians(0.025))
00271 self.pub_vel = True
00272 self.vel_msg.twist.angular.x = x
00273 self.vel_msg.twist.angular.y = y
00274 self.vel_msg.twist.angular.z = z
00275 except KeyError:
00276 pass
00277 try:
00278 self.pub_imu = True
00279 x, y, z = convert_coords(imu_data['accX'], imu_data['accY'],
00280 imu_data['accZ'], o['frame'])
00281 self.imu_msg.linear_acceleration.x = x
00282 self.imu_msg.linear_acceleration.y = y
00283 self.imu_msg.linear_acceleration.z = z
00284 self.imu_msg.linear_acceleration_covariance = (0.0004, 0., 0.,
00285 0., 0.0004, 0.,
00286 0., 0., 0.0004)
00287 except KeyError:
00288 pass
00289 try:
00290 self.pub_mag = True
00291 x, y, z = convert_coords(imu_data['magX'], imu_data['magY'],
00292 imu_data['magZ'], o['frame'])
00293 self.mag_msg.magnetic_field.x = x
00294 self.mag_msg.magnetic_field.y = y
00295 self.mag_msg.magnetic_field.z = z
00296 except KeyError:
00297 pass
00298
00299 def fill_from_Orient(orient_data):
00300 '''Fill messages with information from 'orientation' MTData block.
00301 '''
00302 self.pub_imu = True
00303 if 'quaternion' in orient_data:
00304 w, x, y, z = orient_data['quaternion']
00305 elif 'roll' in orient_data:
00306 x, y, z, w = quaternion_from_euler(
00307 radians(orient_data['roll']), radians(orient_data['pitch']),
00308 radians(orient_data['yaw']))
00309 elif 'matrix' in orient_data:
00310 m = identity_matrix()
00311 m[:3, :3] = orient_data['matrix']
00312 x, y, z, w = quaternion_from_matrix(m)
00313 self.imu_msg.orientation.x = x
00314 self.imu_msg.orientation.y = y
00315 self.imu_msg.orientation.z = z
00316 self.imu_msg.orientation.w = w
00317 self.imu_msg.orientation_covariance = (radians(1.), 0., 0.,
00318 0., radians(1.), 0.,
00319 0., 0., radians(9.))
00320
00321 def fill_from_Auxiliary(aux_data):
00322 '''Fill messages with information from 'Auxiliary' MTData block.'''
00323 try:
00324 self.anin1_msg.data = o['Ain_1']
00325 self.pub_anin1 = True
00326 except KeyError:
00327 pass
00328 try:
00329 self.anin2_msg.data = o['Ain_2']
00330 self.pub_anin2 = True
00331 except KeyError:
00332 pass
00333
00334 def fill_from_Pos(position_data):
00335 '''Fill messages with information from 'position' MTData block.'''
00336 self.pub_gps = True
00337 self.gps_msg.latitude = position_data['Lat']
00338 self.gps_msg.longitude = position_data['Lon']
00339 self.gps_msg.altitude = position_data['Alt']
00340
00341 def fill_from_Vel(velocity_data):
00342 '''Fill messages with information from 'velocity' MTData block.'''
00343 self.pub_vel = True
00344 x, y, z = convert_coords(
00345 velocity_data['Vel_X'], velocity_data['Vel_Y'],
00346 velocity_data['Vel_Z'], o['frame'])
00347 self.vel_msg.twist.linear.x = x
00348 self.vel_msg.twist.linear.y = y
00349 self.vel_msg.twist.linear.z = z
00350
00351 def fill_from_Stat(status):
00352 '''Fill messages with information from 'status' MTData block.'''
00353 self.pub_diag = True
00354 if status & 0b0001:
00355 self.stest_stat.level = DiagnosticStatus.OK
00356 self.stest_stat.message = "Ok"
00357 else:
00358 self.stest_stat.level = DiagnosticStatus.ERROR
00359 self.stest_stat.message = "Failed"
00360 if status & 0b0010:
00361 self.xkf_stat.level = DiagnosticStatus.OK
00362 self.xkf_stat.message = "Valid"
00363 else:
00364 self.xkf_stat.level = DiagnosticStatus.WARN
00365 self.xkf_stat.message = "Invalid"
00366 if status & 0b0100:
00367 self.gps_stat.level = DiagnosticStatus.OK
00368 self.gps_stat.message = "Ok"
00369 self.gps_msg.status.status = NavSatStatus.STATUS_FIX
00370 self.gps_msg.status.service = NavSatStatus.SERVICE_GPS
00371 else:
00372 self.gps_stat.level = DiagnosticStatus.WARN
00373 self.gps_stat.message = "No fix"
00374 self.gps_msg.status.status = NavSatStatus.STATUS_NO_FIX
00375 self.gps_msg.status.service = 0
00376
00377 def fill_from_Sample(ts):
00378 '''Catch 'Sample' MTData blocks.'''
00379 self.h.seq = ts
00380
00381
00382 def fill_from_Temperature(o):
00383 '''Fill messages with information from 'Temperature' MTData2 block.
00384 '''
00385 self.pub_temp = True
00386 self.temp_msg.temperature = o['Temp']
00387
00388 def fill_from_Timestamp(o):
00389 '''Fill messages with information from 'Timestamp' MTData2 block.'''
00390 try:
00391
00392 y, m, d, hr, mi, s, ns, f = o['Year'], o['Month'], o['Day'],\
00393 o['Hour'], o['Minute'], o['Second'], o['ns'], o['Flags']
00394 if f & 0x4:
00395 secs = time.mktime((y, m, d, hr, mi, s, 0, 0, 0))
00396 publish_time_ref(secs, ns, 'UTC time')
00397 except KeyError:
00398 pass
00399 try:
00400 itow = o['TimeOfWeek']
00401 secs, nsecs = stamp_from_itow(itow)
00402 publish_time_ref(secs, nsecs, 'integer time of week')
00403 except KeyError:
00404 pass
00405 try:
00406 sample_time_fine = o['SampleTimeFine']
00407 secs = int(sample_time_fine / 1000)
00408 nsecs = 1e6 * (sample_time_fine % 1000)
00409 publish_time_ref(secs, nsecs, 'sample time fine')
00410 except KeyError:
00411 pass
00412 try:
00413 sample_time_coarse = o['SampleTimeCoarse']
00414 publish_time_ref(sample_time_coarse, 0, 'sample time coarse')
00415 except KeyError:
00416 pass
00417
00418 pass
00419
00420 def fill_from_Orientation_Data(o):
00421 '''Fill messages with information from 'Orientation Data' MTData2
00422 block.'''
00423 self.pub_imu = True
00424 try:
00425 x, y, z, w = o['Q1'], o['Q2'], o['Q3'], o['Q0']
00426 except KeyError:
00427 pass
00428 try:
00429 x, y, z, w = quaternion_from_euler(radians(o['Roll']),
00430 radians(o['Pitch']),
00431 radians(o['Yaw']))
00432 except KeyError:
00433 pass
00434 try:
00435 a, b, c, d, e, f, g, h, i = o['a'], o['b'], o['c'], o['d'],\
00436 o['e'], o['f'], o['g'], o['h'], o['i']
00437 m = identity_matrix()
00438 m[:3, :3] = ((a, b, c), (d, e, f), (g, h, i))
00439 x, y, z, w = quaternion_from_matrix(m)
00440 except KeyError:
00441 pass
00442 w, x, y, z = convert_quat((w, x, y, z), o['frame'])
00443 self.imu_msg.orientation.x = x
00444 self.imu_msg.orientation.y = y
00445 self.imu_msg.orientation.z = z
00446 self.imu_msg.orientation.w = w
00447 self.imu_msg.orientation_covariance = (radians(1.), 0., 0.,
00448 0., radians(1.), 0.,
00449 0., 0., radians(9.))
00450
00451 def fill_from_Pressure(o):
00452 '''Fill messages with information from 'Pressure' MTData2 block.'''
00453 self.press_msg.fluid_pressure = o['Pressure']
00454 self.pub_press = True
00455
00456 def fill_from_Acceleration(o):
00457 '''Fill messages with information from 'Acceleration' MTData2
00458 block.'''
00459 self.pub_imu = True
00460
00461
00462 try:
00463 x, y, z = o['Delta v.x'], o['Delta v.y'], o['Delta v.z']
00464 except KeyError:
00465 pass
00466 try:
00467 x, y, z = o['freeAccX'], o['freeAccY'], o['freeAccZ']
00468 except KeyError:
00469 pass
00470 try:
00471 x, y, z = o['accX'], o['accY'], o['accZ']
00472 except KeyError:
00473 pass
00474 x, y, z = convert_coords(x, y, z, o['frame'])
00475 self.imu_msg.linear_acceleration.x = x
00476 self.imu_msg.linear_acceleration.y = y
00477 self.imu_msg.linear_acceleration.z = z
00478 self.imu_msg.linear_acceleration_covariance = (0.0004, 0., 0.,
00479 0., 0.0004, 0.,
00480 0., 0., 0.0004)
00481
00482 def fill_from_Position(o):
00483 '''Fill messages with information from 'Position' MTData2 block.'''
00484 try:
00485 self.gps_msg.latitude = o['lat']
00486 self.gps_msg.longitude = o['lon']
00487 self.pub_gps = True
00488
00489 alt = o.get('altEllipsoid', o.get('altMsl', 0))
00490 self.gps_msg.altitude = alt
00491 except KeyError:
00492 pass
00493 try:
00494 x, y, z = o['ecefX'], o['ecefY'], o['ecefZ']
00495
00496 self.ecef_msg.point.x = x
00497 self.ecef_msg.point.y = y
00498 self.ecef_msg.point.z = z
00499 self.pub_ecef = True
00500 except KeyError:
00501 pass
00502
00503 def fill_from_GNSS(o):
00504 '''Fill messages with information from 'GNSS' MTData2 block.'''
00505 try:
00506
00507 itow, y, m, d, ns, f = o['itow'], o['year'], o['month'],\
00508 o['day'], o['nano'], o['valid']
00509 if f & 0x4:
00510 secs, nsecs = stamp_from_itow(itow, y, m, d, ns)
00511 publish_time_ref(secs, nsecs, 'GNSS time UTC')
00512
00513 fixtype = o['fixtype']
00514 if fixtype == 0x00:
00515 self.gps_msg.status.status = NavSatStatus.STATUS_NO_FIX
00516 self.gps_msg.status.service = 0
00517 else:
00518 self.gps_msg.status.status = NavSatStatus.STATUS_FIX
00519 self.gps_msg.status.service = NavSatStatus.SERVICE_GPS
00520
00521 self.gps_msg.latitude = o['lat']
00522 self.gps_msg.longitude = o['lon']
00523 self.gps_msg.altitude = o['height']/1e3
00524 self.pub_gps = True
00525
00526
00527
00528 except KeyError:
00529 pass
00530
00531
00532 def fill_from_Angular_Velocity(o):
00533 '''Fill messages with information from 'Angular Velocity' MTData2
00534 block.'''
00535 try:
00536 dqw, dqx, dqy, dqz = convert_quat(
00537 (o['Delta q0'], o['Delta q1'], o['Delta q2'],
00538 o['Delta q3']),
00539 o['frame'])
00540 now = rospy.Time.now()
00541 if self.last_delta_q_time is None:
00542 self.last_delta_q_time = now
00543 else:
00544
00545 delta_t = (now - self.last_delta_q_time).to_sec()
00546 if self.delta_q_rate is None:
00547 self.delta_q_rate = 1./delta_t
00548 delta_t_filtered = .95/self.delta_q_rate + .05*delta_t
00549
00550 self.delta_q_rate = round(1./delta_t_filtered)
00551 self.last_delta_q_time = now
00552
00553
00554
00555
00556
00557 ca_2, sa_2 = dqw, sqrt(dqx**2 + dqy**2 + dqz**2)
00558 ca = ca_2**2 - sa_2**2
00559 sa = 2*ca_2*sa_2
00560 rotation_angle = atan2(sa, ca)
00561
00562 rotation_speed = rotation_angle * self.delta_q_rate
00563 f = rotation_speed / sa_2
00564 x, y, z = f*dqx, f*dqy, f*dqz
00565 self.imu_msg.angular_velocity.x = x
00566 self.imu_msg.angular_velocity.y = y
00567 self.imu_msg.angular_velocity.z = z
00568 self.imu_msg.angular_velocity_covariance = (
00569 radians(0.025), 0., 0.,
00570 0., radians(0.025), 0.,
00571 0., 0., radians(0.025))
00572 self.pub_imu = True
00573 self.vel_msg.twist.angular.x = x
00574 self.vel_msg.twist.angular.y = y
00575 self.vel_msg.twist.angular.z = z
00576 self.pub_vel = True
00577 except KeyError:
00578 pass
00579 try:
00580 x, y, z = convert_coords(o['gyrX'], o['gyrY'], o['gyrZ'],
00581 o['frame'])
00582 self.imu_msg.angular_velocity.x = x
00583 self.imu_msg.angular_velocity.y = y
00584 self.imu_msg.angular_velocity.z = z
00585 self.imu_msg.angular_velocity_covariance = (
00586 radians(0.025), 0., 0.,
00587 0., radians(0.025), 0.,
00588 0., 0., radians(0.025))
00589 self.pub_imu = True
00590 self.vel_msg.twist.angular.x = x
00591 self.vel_msg.twist.angular.y = y
00592 self.vel_msg.twist.angular.z = z
00593 self.pub_vel = True
00594 except KeyError:
00595 pass
00596
00597 def fill_from_GPS(o):
00598 '''Fill messages with information from 'GPS' MTData2 block.'''
00599
00600 try:
00601 x, y, z = o['ecefX'], o['ecefY'], o['ecefZ']
00602 self.ecef_msg.point.x = x * 0.01
00603 self.ecef_msg.point.y = y * 0.01
00604 self.ecef_msg.point.z = z * 0.01
00605 self.pub_ecef = True
00606 vx, vy, vz = o['ecefVX'], o['ecefVY'], o['ecefVZ']
00607 self.vel_msg.twist.linear.x = vx * 0.01
00608 self.vel_msg.twist.linear.y = vy * 0.01
00609 self.vel_msg.twist.linear.z = vz * 0.01
00610 self.pub_vel = True
00611 itow, ns, week, f = o['iTOW'], o['fTOW'], o['Week'], o['Flags']
00612 if (f & 0x0C) == 0xC:
00613 secs, nsecs = stamp_from_itow(itow, ns=ns, week=week)
00614 publish_time_ref(secs, nsecs, 'GPS Time')
00615
00616
00617 except KeyError:
00618 pass
00619 try:
00620 itow, y, m, d, ns, f = o['iTOW'], o['year'], o['month'],\
00621 o['day'], o['nano'], o['valid']
00622 if f & 0x4:
00623 secs, nsecs = stamp_from_itow(itow, y, m, d, ns)
00624 publish_time_ref(secs, nsecs, 'GPS Time UTC')
00625 except KeyError:
00626 pass
00627
00628
00629 def fill_from_SCR(o):
00630 '''Fill messages with information from 'SCR' MTData2 block.'''
00631
00632 pass
00633
00634 def fill_from_Analog_In(o):
00635 '''Fill messages with information from 'Analog In' MTData2 block.'''
00636 try:
00637 self.anin1_msg.data = o['analogIn1']
00638 self.pub_anin1 = True
00639 except KeyError:
00640 pass
00641 try:
00642 self.anin2_msg.data = o['analogIn2']
00643 self.pub_anin2 = True
00644 except KeyError:
00645 pass
00646
00647 def fill_from_Magnetic(o):
00648 '''Fill messages with information from 'Magnetic' MTData2 block.'''
00649 x, y, z = convert_coords(o['magX'], o['magY'], o['magZ'],
00650 o['frame'])
00651 self.mag_msg.magnetic_field.x = x
00652 self.mag_msg.magnetic_field.y = y
00653 self.mag_msg.magnetic_field.z = z
00654 self.pub_mag = True
00655
00656 def fill_from_Velocity(o):
00657 '''Fill messages with information from 'Velocity' MTData2 block.'''
00658 x, y, z = convert_coords(o['velX'], o['velY'], o['velZ'],
00659 o['frame'])
00660 self.vel_msg.twist.linear.x = x
00661 self.vel_msg.twist.linear.y = y
00662 self.vel_msg.twist.linear.z = z
00663 self.pub_vel = True
00664
00665 def fill_from_Status(o):
00666 '''Fill messages with information from 'Status' MTData2 block.'''
00667 try:
00668 status = o['StatusByte']
00669 fill_from_Stat(status)
00670 except KeyError:
00671 pass
00672 try:
00673 status = o['StatusWord']
00674 fill_from_Stat(status)
00675 except KeyError:
00676 pass
00677
00678 def find_handler_name(name):
00679 return "fill_from_%s" % (name.replace(" ", "_"))
00680
00681
00682 try:
00683 data = self.mt.read_measurement()
00684 except mtdef.MTTimeoutException:
00685 time.sleep(0.1)
00686 return
00687
00688 self.h = Header()
00689 self.h.stamp = rospy.Time.now()
00690 self.h.frame_id = self.frame_id
00691
00692
00693 self.reset_vars()
00694
00695
00696 for n, o in data.items():
00697 try:
00698 locals()[find_handler_name(n)](o)
00699 except KeyError:
00700 rospy.logwarn("Unknown MTi data packet: '%s', ignoring." % n)
00701
00702
00703 if self.pub_imu:
00704 self.imu_msg.header = self.h
00705 if self.imu_pub is None:
00706 self.imu_pub = rospy.Publisher('imu/data', Imu, queue_size=10)
00707 self.imu_pub.publish(self.imu_msg)
00708 if self.pub_gps:
00709 self.gps_msg.header = self.h
00710 if self.gps_pub is None:
00711 self.gps_pub = rospy.Publisher('fix', NavSatFix, queue_size=10)
00712 self.gps_pub.publish(self.gps_msg)
00713 if self.pub_vel:
00714 self.vel_msg.header = self.h
00715 if self.vel_pub is None:
00716 self.vel_pub = rospy.Publisher('velocity', TwistStamped,
00717 queue_size=10)
00718 self.vel_pub.publish(self.vel_msg)
00719 if self.pub_mag:
00720 self.mag_msg.header = self.h
00721 if self.mag_pub is None:
00722 self.mag_pub = rospy.Publisher('imu/mag', MagneticField,
00723 queue_size=10)
00724 self.mag_pub.publish(self.mag_msg)
00725 if self.pub_temp:
00726 self.temp_msg.header = self.h
00727 if self.temp_pub is None:
00728 self.temp_pub = rospy.Publisher('temperature', Temperature,
00729 queue_size=10)
00730 self.temp_pub.publish(self.temp_msg)
00731 if self.pub_press:
00732 self.press_msg.header = self.h
00733 if self.press_pub is None:
00734 self.press_pub = rospy.Publisher('pressure', FluidPressure,
00735 queue_size=10)
00736 self.press_pub.publish(self.press_msg)
00737 if self.pub_anin1:
00738 if self.analog_in1_pub is None:
00739 self.analog_in1_pub = rospy.Publisher('analog_in1',
00740 UInt16, queue_size=10)
00741 self.analog_in1_pub.publish(self.anin1_msg)
00742 if self.pub_anin2:
00743 if self.analog_in2_pub is None:
00744 self.analog_in2_pub = rospy.Publisher('analog_in2', UInt16,
00745 queue_size=10)
00746 self.analog_in2_pub.publish(self.anin2_msg)
00747 if self.pub_ecef:
00748 self.ecef_msg.header = self.h
00749 if self.ecef_pub is None:
00750 self.ecef_pub = rospy.Publisher('ecef', PointStamped,
00751 queue_size=10)
00752 self.ecef_pub.publish(self.ecef_msg)
00753 if self.pub_diag:
00754 self.diag_msg.header = self.h
00755 if self.diag_pub is None:
00756 self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray,
00757 queue_size=10)
00758 self.diag_pub.publish(self.diag_msg)
00759
00760 self.str_pub.publish(str(data))
00761
00762
00763 def main():
00764 '''Create a ROS node and instantiate the class.'''
00765 rospy.init_node('xsens_driver')
00766 driver = XSensDriver()
00767 driver.spin()
00768
00769
00770 if __name__ == '__main__':
00771 main()