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