rs-imu-calibration.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 from __future__ import print_function
3 import numpy as np
4 import sys
5 import json
6 import ctypes
7 import os
8 import binascii
9 import struct
10 import pyrealsense2 as rs
11 import ctypes
12 import time
13 import enum
14 import threading
15 
16 # L515
17 READ_TABLE = 0x43 # READ_TABLE 0x243 0
18 WRITE_TABLE = 0x44 # WRITE_TABLE 0 <table>
19 
20 # L515 minimum firmware version required to support IMU calibration
21 L515_FW_VER_REQUIRED = '01.04.01.00'
22 
23 is_data = None
24 get_key = None
25 if os.name == 'posix':
26  import select
27  import tty
28  import termios
29 
30  is_data = lambda : select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], [])
31  get_key = lambda : sys.stdin.read(1)
32 
33 elif os.name == 'nt':
34  import msvcrt
35  is_data = msvcrt.kbhit
36  get_key = lambda : msvcrt.getch()
37 
38 else:
39  raise Exception('Unsupported OS: %s' % os.name)
40 
41 if sys.version_info[0] < 3:
42  input = raw_input
43 
44 max_float = struct.unpack('f',b'\xff\xff\xff\xff')[0]
45 max_int = struct.unpack('i',b'\xff\xff\xff\xff')[0]
46 max_uint8 = struct.unpack('B', b'\xff')[0]
47 
48 g = 9.80665 # SI Gravity page 52 of https://nvlpubs.nist.gov/nistpubs/Legacy/SP/nistspecialpublication330e2008.pdf
49 
50 COLOR_RED = "\033[1;31m"
51 COLOR_BLUE = "\033[1;34m"
52 COLOR_CYAN = "\033[1;36m"
53 COLOR_GREEN = "\033[0;32m"
54 COLOR_RESET = "\033[0;0m"
55 COLOR_BOLD = "\033[;1m"
56 COLOR_REVERSE = "\033[;7m"
57 
58 def int_to_bytes(num, length=4, order='big'):
59  res = bytearray(length)
60  for i in range(length):
61  res[i] = num & 0xff
62  num >>= 8
63  if num:
64  raise OverflowError("Number {} doesn't fit into {} bytes.".format(num, length))
65  if order == 'little':
66  res.reverse()
67  return res
68 
69 
70 def bytes_to_uint(bytes_array, order='little'):
71  bytes_array = list(bytes_array)
72  bytes_array.reverse()
73  if order == 'little':
74  return struct.unpack('>i', struct.pack('BBBB', *([0] * (4 - len(bytes_array))) + bytes_array))[0] & 0xffffffff
75  else:
76  return struct.unpack('>i', struct.pack('BBBB', *([0] * (4 - len(bytes_array))) + bytes_array))[0] & 0xffffffff
77 
78 
80  class Status(enum.Enum):
81  idle = 0,
82  rotate = 1,
83  wait_to_stable = 2,
84  collect_data = 3
85 
86  def __init__(self):
87  self.pipeline = None
88  self.imu_sensor = None
89  self.status = self.Status(self.Status.idle) # 0 - idle, 1 - rotate to position, 2 - wait to stable, 3 - pick data
90  self.thread = threading.Condition()
91  self.step_start_time = time.time()
92  self.time_to_stable = 3
93  self.time_to_collect = 2
94  self.samples_to_collect = 1000
95  self.rotating_threshold = 0.1
99  self.callback_lock = threading.Lock()
100  self.max_norm = np.linalg.norm(np.array([0.5, 0.5, 0.5]))
101  self.line_length = 20
102  self.is_done = False
103  self.is_data = False
104 
105  def escape_handler(self):
106  self.thread.acquire()
107  self.status = self.Status.idle
108  self.is_done = True
109  self.thread.notify()
110  self.thread.release()
111  sys.exit(-1)
112 
113  def imu_callback(self, frame):
114  if not self.is_data:
115  self.is_data = True
116 
117  with self.callback_lock:
118  try:
119  if is_data():
120  c = get_key()
121  if c == '\x1b': # x1b is ESC
122  self.escape_handler()
123 
124  if self.status == self.Status.idle:
125  return
126  pr = frame.get_profile()
127  data = frame.as_motion_frame().get_motion_data()
128  data_np = np.array([data.x, data.y, data.z])
129  elapsed_time = time.time() - self.step_start_time
130 
131  ## Status.collect_data
132  if self.status == self.Status.collect_data:
133  sys.stdout.write('\r %15s' % self.status)
134  part_done = len(self.collected_data_accel) / float(self.samples_to_collect)
135  # sys.stdout.write(': %-3.1f (secs)' % (self.time_to_collect - elapsed_time))
136 
137  color = COLOR_GREEN
138  if pr.stream_type() == rs.stream.gyro:
139  self.collected_data_gyro.append(np.append(frame.get_timestamp(), data_np))
140  is_moving = any(abs(data_np) > self.rotating_threshold)
141  else:
142  is_in_norm = np.linalg.norm(data_np - self.crnt_bucket) < self.max_norm
143  if is_in_norm:
144  self.collected_data_accel.append(np.append(frame.get_timestamp(), data_np))
145  else:
146  color = COLOR_RED
147  is_moving = abs(np.linalg.norm(data_np) - g) / g > self.moving_threshold_factor
148 
149  sys.stdout.write(color)
150  sys.stdout.write('['+'.'*int(part_done*self.line_length)+' '*int((1-part_done)*self.line_length) + ']')
151  sys.stdout.write(COLOR_RESET)
152 
153  if is_moving:
154  print('WARNING: MOVING')
155  self.status = self.Status.rotate
156  return
157 
158  # if elapsed_time > self.time_to_collect:
159  if part_done >= 1:
160  self.status = self.Status.collect_data
161  sys.stdout.write('\n\nDirection data collected.')
162  self.thread.acquire()
163  self.status = self.Status.idle
164  self.thread.notify()
165  self.thread.release()
166  return
167 
168  if pr.stream_type() == rs.stream.gyro:
169  return
170  sys.stdout.write('\r %15s' % self.status)
171  crnt_dir = np.array(data_np) / np.linalg.norm(data_np)
172  crnt_diff = self.crnt_direction - crnt_dir
173  is_in_norm = np.linalg.norm(data_np - self.crnt_bucket) < self.max_norm
174 
175  ## Status.rotate
176  if self.status == self.Status.rotate:
177  sys.stdout.write(': %35s' % (np.array2string(crnt_diff, precision=4, suppress_small=True)))
178  sys.stdout.write(': %35s' % (np.array2string(abs(crnt_diff) < 0.1)))
179  if is_in_norm:
180  self.status = self.Status.wait_to_stable
181  sys.stdout.write('\r'+' '*90)
182  self.step_start_time = time.time()
183  return
184 
185  ## Status.wait_to_stable
186  if self.status == self.Status.wait_to_stable:
187  sys.stdout.write(': %-3.1f (secs)' % (self.time_to_stable - elapsed_time))
188  if not is_in_norm:
189  self.status = self.Status.rotate
190  return
191  if elapsed_time > self.time_to_stable:
192  self.collected_data_gyro = []
193  self.collected_data_accel = []
194  self.status = self.Status.collect_data
195  self.step_start_time = time.time()
196  return
197  return
198  except Exception as e:
199  print('ERROR?' + str(e))
200  self.thread.acquire()
201  self.status = self.Status.idle
202  self.thread.notify()
203  self.thread.release()
204 
205  def get_measurements(self, buckets, bucket_labels):
206  measurements = []
207  print('-------------------------')
208  print('*** Press ESC to Quit ***')
209  print('-------------------------')
210  for bucket,bucket_label in zip(buckets, bucket_labels):
211  self.crnt_bucket = np.array(bucket)
212  self.crnt_direction = np.array(bucket) / np.linalg.norm(np.array(bucket))
213  print('\nAlign to direction: ', self.crnt_direction, ' ', bucket_label)
214  self.status = self.Status.rotate
215  self.thread.acquire()
216  while (not self.is_done and self.status != self.Status.idle):
217  self.thread.wait(3)
218  if not self.is_data:
219  raise Exception('No IMU data. Check connectivity.')
220  if self.is_done:
221  raise Exception('User Abort.')
222  measurements.append(np.array(self.collected_data_accel))
223  return np.array(measurements), np.array(self.collected_data_gyro)
224 
225  def enable_imu_device(self, serial_no):
226  self.pipeline = rs.pipeline()
227  cfg = rs.config()
228  cfg.enable_device(serial_no)
229  try:
230  self.pipeline.start(cfg)
231  except Exception as e:
232  print('ERROR: ', str(e))
233  return False
234 
235  # self.sync_imu_by_this_stream = rs.stream.any
236  active_imu_profiles = []
237 
238  active_profiles = dict()
239  self.imu_sensor = None
240  for sensor in self.pipeline.get_active_profile().get_device().sensors:
241  for pr in sensor.get_stream_profiles():
242  if pr.stream_type() == rs.stream.gyro and pr.format() == rs.format.motion_xyz32f:
243  active_profiles[pr.stream_type()] = pr
244  self.imu_sensor = sensor
245  if pr.stream_type() == rs.stream.accel and pr.format() == rs.format.motion_xyz32f:
246  active_profiles[pr.stream_type()] = pr
247  self.imu_sensor = sensor
248  if self.imu_sensor:
249  break
250  if not self.imu_sensor:
251  print('No IMU sensor found.')
252  return False
253  print('\n'.join(['FOUND %s with fps=%s' % (str(ap[0]).split('.')[1].upper(), ap[1].fps()) for ap in active_profiles.items()]))
254  active_imu_profiles = list(active_profiles.values())
255  if len(active_imu_profiles) < 2:
256  print('Not all IMU streams found.')
257  return False
258  self.imu_sensor.stop()
259  self.imu_sensor.close()
260  self.imu_sensor.open(active_imu_profiles)
261  self.imu_start_loop_time = time.time()
262  self.imu_sensor.start(self.imu_callback)
263 
264  # Make the device use the original IMU values and not already calibrated:
265  if self.imu_sensor.supports(rs.option.enable_motion_correction):
266  self.imu_sensor.set_option(rs.option.enable_motion_correction, 0)
267  return True
268 
269 class CHeader:
270  def __init__(self, version, table_type):
271  self.buffer = np.ones(16, dtype=np.uint8) * 255
272  self.buffer[0] = int(version[0], 16)
273  self.buffer[1] = int(version[1], 16)
274  self.buffer.dtype=np.uint16
275  self.buffer[1] = int(table_type, 16)
276 
277  def size(self):
278  return 16
279 
280  def set_data_size(self, size):
281  self.buffer.dtype=np.uint32
282  self.buffer[1] = size
283 
284  def set_crc32(self, crc32):
285  self.buffer.dtype=np.uint32
286  self.buffer[3] = crc32 % (1<<32) # convert from signed to unsigned 32 bit
287 
288  def get_buffer(self):
289  self.buffer.dtype=np.uint8
290  return self.buffer
291 
292 
294  return struct.unpack('f', struct.pack('i', ival))[0]
295 
297  return struct.unpack('i', struct.pack('f', fval))[0]
298 
299 def parse_buffer(buffer):
300  cmd_size = 24
301  header_size = 16
302 
303  buffer.dtype=np.uint32
304  tab1_size = buffer[3]
305  buffer.dtype=np.uint8
306  print('tab1_size (all_data): ', tab1_size)
307 
308  tab1 = buffer[cmd_size:cmd_size+tab1_size] # 520 == epprom++
309  tab1.dtype=np.uint32
310  tab2_size = tab1[1]
311  tab1.dtype=np.uint8
312  print('tab2_size (calibration_table): ', tab2_size)
313 
314  tab2 = tab1[header_size:header_size+tab2_size] # calibration table
315  tab2.dtype=np.uint32
316  tab3_size = tab2[1]
317  tab2.dtype=np.uint8
318  print('tab3_size (calibration_table): ', tab3_size)
319 
320  tab3 = tab2[header_size:header_size+tab3_size] # D435 IMU Calib Table
321  tab3.dtype=np.uint32
322  tab4_size = tab3[1]
323  tab3.dtype=np.uint8
324  print('tab4_size (D435_IMU_Calib_Table): ', tab4_size)
325 
326  tab4 = tab3[header_size:header_size+tab4_size] # calibration data
327  return tab1, tab2, tab3, tab4
328 
329 def get_IMU_Calib_Table(X, product_line):
330  version = ['0x02', '0x01']
331  table_type = '0x20'
332 
333  if product_line == 'L500':
334  version = ['0x05', '0x01']
335  table_type = '0x243'
336 
337  header = CHeader(version, table_type)
338 
339  header_size = header.size()
340  data_size = 37*4 + 96
341  size_of_buffer = header_size + data_size # according to table "D435 IMU Calib Table" here: https://user-images.githubusercontent.com/6958867/50902974-20507500-1425-11e9-8ca5-8bd2ac2d0ea1.png
342  assert(size_of_buffer % 4 == 0)
343  buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
344 
345  use_extrinsics = False
346  use_intrinsics = True
347 
348  data_buffer = np.ones(data_size, dtype=np.uint8) * 255
349  data_buffer.dtype = np.float32
350 
351  data_buffer[0] = bitwise_int_to_float(np.int32(int(use_intrinsics)) << 8 |
352  np.int32(int(use_extrinsics)))
353 
354  intrinsic_vector = np.zeros(24, dtype=np.float32)
355  intrinsic_vector[:9] = X[:3,:3].T.flatten()
356  intrinsic_vector[9:12] = X[:3,3]
357  intrinsic_vector[12:21] = X[3:,:3].flatten()
358  intrinsic_vector[21:24] = X[3:,3]
359 
360  data_buffer[13:13+X.size] = intrinsic_vector
361  data_buffer.dtype = np.uint8
362 
363  header.set_data_size(data_size)
364 
365  header.set_crc32(binascii.crc32(data_buffer))
366  buffer[:header_size] = header.get_buffer()
367  buffer[header_size:] = data_buffer
368  return buffer
369 
370 
371 def get_calibration_table(d435_imu_calib_table):
372  version = ['0x02', '0x00']
373  table_type = '0x20'
374 
375  header = CHeader(version, table_type)
376 
377  d435_imu_calib_table_size = d435_imu_calib_table.size
378  sn_table_size = 32
379  data_size = d435_imu_calib_table_size + sn_table_size
380 
381  header_size = header.size()
382  size_of_buffer = header_size + data_size # according to table "D435 IMU Calib Table" in "https://sharepoint.ger.ith.intel.com/sites/3D_project/Shared%20Documents/Arch/D400/FW/D435i_IMU_Calibration_eeprom_0_52.xlsx"
383  assert(size_of_buffer % 4 == 0)
384  buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
385 
386  data_buffer = np.ones(data_size, dtype=np.uint8) * 255
387  data_buffer[:d435_imu_calib_table_size] = d435_imu_calib_table
388 
389  header.set_data_size(data_size)
390  header.set_crc32(binascii.crc32(data_buffer))
391 
392  buffer[:header_size] = header.get_buffer()
393  buffer[header_size:header_size+data_size] = data_buffer
394  return buffer
395 
396 def get_eeprom(calibration_table):
397  version = ['0x01', '0x01']
398  table_type = '0x09'
399 
400  header = CHeader(version, table_type)
401 
402  DC_MM_EEPROM_SIZE = 520
403  # data_size = calibration_table.size
404 
405  header_size = header.size()
406  size_of_buffer = DC_MM_EEPROM_SIZE
407  data_size = size_of_buffer - header_size
408  # size_of_buffer = header_size + data_size
409 
410  assert(size_of_buffer % 4 == 0)
411  buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
412 
413  header.set_data_size(data_size)
414  buffer[header_size:header_size+calibration_table.size] = calibration_table
415  header.set_crc32(binascii.crc32(buffer[header_size:]))
416 
417  buffer[:header_size] = header.get_buffer()
418 
419  return buffer
420 
421 def write_eeprom_to_camera(eeprom, serial_no=''):
422  # DC_MM_EEPROM_SIZE = 520
423  DC_MM_EEPROM_SIZE = eeprom.size
424  DS5_CMD_LENGTH = 24
425 
426  MMEW_Cmd_bytes = b'\x14\x00\xab\xcd\x50\x00\x00\x00\x00\x00\x00\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'
427 
428 
429  buffer = np.ones([DC_MM_EEPROM_SIZE + DS5_CMD_LENGTH, ], dtype = np.uint8) * 255
430  cmd = np.array(struct.unpack('I'*6, MMEW_Cmd_bytes), dtype=np.uint32)
431  cmd.dtype = np.uint16
432  cmd[0] += DC_MM_EEPROM_SIZE
433  cmd.dtype = np.uint32
434  cmd[3] = DC_MM_EEPROM_SIZE # command 1 = 0x50
435  # command 2 = 0
436  # command 3 = size
437  cmd.dtype = np.uint8
438  buffer[:len(cmd)] = cmd
439  buffer[len(cmd):len(cmd)+eeprom.size] = eeprom
440 
441  debug = get_debug_device(serial_no)
442  if not debug:
443  print('Error getting RealSense Device.')
444  return
445  # tab1, tab2, tab3, tab4 = parse_buffer(buffer)
446 
447  rcvBuf = debug.send_and_receive_raw_data(bytearray(buffer))
448  if rcvBuf[0] == buffer[4]:
449  print('SUCCESS: saved calibration to camera.')
450  else:
451  print('FAILED: failed to save calibration to camera.')
452  print(rcvBuf)
453 
454 
455 def get_debug_device(serial_no):
456  ctx = rs.context()
457  devices = ctx.query_devices()
458  found_dev = False
459  for dev in devices:
460  if len(serial_no) == 0 or serial_no == dev.get_info(rs.camera_info.serial_number):
461  found_dev = True
462  break
463  if not found_dev:
464  print('No RealSense device found' + str('.' if len(serial_no) == 0 else ' with serial number: '+serial_no))
465  return 0
466 
467  # print(a few basic information about the device)
468  print(' Device PID: ', dev.get_info(rs.camera_info.product_id))
469  print(' Device name: ', dev.get_info(rs.camera_info.name))
470  print(' Serial number: ', dev.get_info(rs.camera_info.serial_number))
471  print(' Firmware version: ', dev.get_info(rs.camera_info.firmware_version))
472  debug = rs.debug_protocol(dev)
473  return debug
474 
475 def check_X(X, accel, show_graph):
476  fdata = np.apply_along_axis(np.dot, 1, accel, X[:3,:3]) - X[3,:]
477  norm_data = (accel**2).sum(axis=1)**(1./2)
478  norm_fdata = (fdata**2).sum(axis=1)**(1./2)
479  if show_graph:
480  import pylab
481  pylab.plot(norm_data, '.b')
482  #pylab.hold(True)
483  pylab.plot(norm_fdata, '.g')
484  pylab.show()
485  print ('norm (raw data ): %f' % np.mean(norm_data))
486  print ('norm (fixed data): %f' % np.mean(norm_fdata), "A good calibration will be near %f" % g)
487 
488 def l500_send_command(dev, op_code, param1=0, param2=0, param3=0, param4=0, data=[], retries=1):
489 
490  for i in range(retries):
491  try:
492  debug_device = rs.debug_protocol(dev)
493  gvd_command_length = 0x14 + len(data)
494  magic_number1 = 0xab
495  magic_number2 = 0xcd
496 
497  buf = bytearray()
498  buf += bytes(int_to_bytes(gvd_command_length, 2))
499  #buf += bytes(int_to_bytes(0, 1))
500  buf += bytes(int_to_bytes(magic_number1, 1))
501  buf += bytes(int_to_bytes(magic_number2, 1))
502  buf += bytes(int_to_bytes(op_code))
503  buf += bytes(int_to_bytes(param1))
504  buf += bytes(int_to_bytes(param2))
505  buf += bytes(int_to_bytes(param3))
506  buf += bytes(int_to_bytes(param4))
507  buf += bytearray(data)
508  l = list(buf)
509  res = debug_device.send_and_receive_raw_data(buf)
510 
511  if res[0] == op_code:
512  res1 = res[4:]
513  return res1
514  else:
515  raise Exception("send_command return error", res[0])
516  except:
517  if i < retries - 1:
518  time.sleep(0.1)
519  else:
520  raise
521 
522 def wait_for_rs_device(serial_no):
523  ctx = rs.context()
524 
525  start = int(round(time.time() * 1000))
526  now = int(round(time.time() * 1000))
527 
528  while now - start < 5000:
529  devices = ctx.query_devices()
530  for dev in devices:
531  pid = str(dev.get_info(rs.camera_info.product_id))
532  if len(serial_no) == 0 or serial_no == dev.get_info(rs.camera_info.serial_number):
533 
534  # print(a few basic information about the device)
535  print(' Device PID: ', dev.get_info(rs.camera_info.product_id))
536  print(' Device name: ', dev.get_info(rs.camera_info.name))
537  print(' Serial number: ', dev.get_info(rs.camera_info.serial_number))
538  print(' Product Line: ', dev.get_info(rs.camera_info.product_line))
539  print(' Firmware version: ', dev.get_info(rs.camera_info.firmware_version))
540 
541  return dev
542  time.sleep(5)
543  now = int(round(time.time() * 1000))
544  raise Exception('No RealSense device' + str('.' if len(serial_no) == 0 else ' with serial number: '+serial_no))
545 
546 
547 def main():
548  if any([help_str in sys.argv for help_str in ['-h', '--help', '/?']]):
549  print("Usage:", sys.argv[0], "[Options]")
550  print
551  print('[Options]:')
552  print('-i : /path/to/accel.txt [/path/to/gyro.txt]')
553  print('-s : serial number of device to calibrate.')
554  print('-g : show graph of norm values - original values in blue and corrected in green.')
555  print
556  print('If -i option is given, calibration is done using previosly saved files')
557  print('Otherwise, an interactive process is followed.')
558  sys.exit(1)
559 
560  try:
561  accel_file = None
562  gyro_file = None
563  serial_no = ''
564  show_graph = '-g' in sys.argv
565  for idx in range(len(sys.argv)):
566  if sys.argv[idx] == '-i':
567  accel_file = sys.argv[idx+1]
568  if len(sys.argv) > idx+2 and not sys.argv[idx+2].startswith('-'):
569  gyro_file = sys.argv[idx+2]
570  if sys.argv[idx] == '-s':
571  serial_no = sys.argv[idx+1]
572 
573  print('waiting for realsense device...')
574 
575  dev = wait_for_rs_device(serial_no)
576 
577  product_line = dev.get_info(rs.camera_info.product_line)
578 
579  if product_line == 'L500':
580  print('checking minimum firmware requirement ...')
581  fw_version = dev.get_info(rs.camera_info.firmware_version)
582  if fw_version < L515_FW_VER_REQUIRED:
583  raise Exception('L515 requires firmware ' + L515_FW_VER_REQUIRED + " or later to support IMU calibration. Please upgrade firmware and try again.")
584  else:
585  print(' firmware ' + fw_version + ' passed check.')
586 
587  buckets = [[0, -g, 0], [ g, 0, 0],
588  [0, g, 0], [-g, 0, 0],
589  [0, 0, -g], [ 0, 0, g]]
590 
591  # all D400 and L500 cameras with IMU equipped with a mounting screw at the bottom of the device
592  # when device is in normal use position upright facing out, mount screw is pointing down, aligned with positive Y direction in depth coordinate system
593  # IMU output on each of these devices is transformed into the depth coordinate system, i.e.,
594  # looking from back of the camera towards front, the positive x-axis points to the right, the positive y-axis points down, and the positive z-axis points forward.
595  # output of motion data is consistent with convention that positive direction aligned with gravity leads to -1g and opposite direction leads to +1g, for example,
596  # positive z_aixs points forward away from front glass of the device,
597  # 1) if place the device flat on a table, facing up, positive z-axis points up, z-axis acceleration is around +1g
598  # 2) facing down, positive z-axis points down, z-axis accleration would be around -1g
599  #
600  buckets_labels = ["Mounting screw pointing down, device facing out", "Mounting screw pointing left, device facing out", "Mounting screw pointing up, device facing out", "Mounting screw pointing right, device facing out", "Viewing direction facing down", "Viewing direction facing up"]
601 
602  gyro_bais = np.zeros(3, np.float32)
603  old_settings = None
604  if accel_file:
605  if gyro_file:
606  #compute gyro bais
607 
608  #assume the first 4 seconds the device is still
609  gyro = np.loadtxt(gyro_file, delimiter=",")
610  gyro = gyro[gyro[:, 0] < gyro[0, 0]+4000, :]
611 
612  gyro_bais = np.mean(gyro[:, 1:], axis=0)
613  print(gyro_bais)
614 
615  #compute accel intrinsic parameters
616  max_norm = np.linalg.norm(np.array([0.5, 0.5, 0.5]))
617 
618  measurements = [[], [], [], [], [], []]
619  import csv
620  with open(accel_file, 'r') as csvfile:
621  reader = csv.reader(csvfile)
622  rnum = 0
623  for row in reader:
624  M = np.array([float(row[1]), float(row[2]), float(row[3])])
625  is_ok = False
626  for i in range(0, len(buckets)):
627  if np.linalg.norm(M - buckets[i]) < max_norm:
628  is_ok = True
629  measurements[i].append(M)
630  rnum += 1
631  print('read %d rows.' % rnum)
632  else:
633  print('Start interactive mode:')
634  if os.name == 'posix':
635  old_settings = termios.tcgetattr(sys.stdin)
636  tty.setcbreak(sys.stdin.fileno())
637 
638  imu = imu_wrapper()
639  if not imu.enable_imu_device(serial_no):
640  print('Failed to enable device.')
641  return -1
642  measurements, gyro = imu.get_measurements(buckets, buckets_labels)
643  con_mm = np.concatenate(measurements)
644  if os.name == 'posix':
645  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)
646 
647  header = input('\nWould you like to save the raw data? Enter footer for saving files (accel_<footer>.txt and gyro_<footer>.txt)\nEnter nothing to not save raw data to disk. >')
648  print('\n')
649  if header:
650  accel_file = 'accel_%s.txt' % header
651  gyro_file = 'gyro_%s.txt' % header
652  print('Writing files:\n%s\n%s' % (accel_file, gyro_file))
653  np.savetxt(accel_file, con_mm, delimiter=',', fmt='%s')
654  np.savetxt(gyro_file, gyro, delimiter=',', fmt='%s')
655  else:
656  print('Not writing to files.')
657  # remove times from measurements:
658  measurements = [mm[:,1:] for mm in measurements]
659 
660  gyro_bais = np.mean(gyro[:, 1:], axis=0)
661  print(gyro_bais)
662 
663  mlen = np.array([len(meas) for meas in measurements])
664  print(mlen)
665  print('using %d measurements.' % mlen.sum())
666 
667  nrows = mlen.sum()
668  w = np.zeros([nrows, 4])
669  Y = np.zeros([nrows, 3])
670  row = 0
671  for i in range(0, len(buckets)):
672  for m in measurements[i]:
673  w[row, 0] = m[0]
674  w[row, 1] = m[1]
675  w[row, 2] = m[2]
676  w[row, 3] = -1
677  Y[row, 0] = buckets[i][0]
678  Y[row, 1] = buckets[i][1]
679  Y[row, 2] = buckets[i][2]
680  row += 1
681  np_version = [int(x) for x in np.version.version.split('.')]
682  rcond_val = None if (np_version[1] >= 14 or np_version[0] > 1) else -1
683  X, residuals, rank, singular = np.linalg.lstsq(w, Y, rcond=rcond_val)
684 
685  print(X)
686  print("residuals:", residuals)
687  print("rank:", rank)
688  print("singular:", singular)
689  check_X(X, w[:,:3], show_graph)
690 
691  calibration = {}
692 
693  if product_line == 'L500':
694  calibration["device_type"] = "L515"
695  else:
696  calibration["device_type"] = "D435i"
697 
698  calibration["imus"] = list()
699  calibration["imus"].append({})
700  calibration["imus"][0]["accelerometer"] = {}
701  calibration["imus"][0]["accelerometer"]["scale_and_alignment"] = X.flatten()[:9].tolist()
702  calibration["imus"][0]["accelerometer"]["bias"] = X.flatten()[9:].tolist()
703  calibration["imus"][0]["gyroscope"] = {}
704  calibration["imus"][0]["gyroscope"]["scale_and_alignment"] = np.eye(3).flatten().tolist()
705  calibration["imus"][0]["gyroscope"]["bias"] = gyro_bais.tolist()
706  json_data = json.dumps(calibration, indent=4, sort_keys=True)
707 
708  directory = os.path.dirname(accel_file) if accel_file else '.'
709 
710  with open(os.path.join(directory,"calibration.json"), 'w') as outfile:
711  outfile.write(json_data)
712 
713  #concatinate the two 12 element arrays and save
714  intrinsic_buffer = np.zeros([6,4])
715 
716  intrinsic_buffer[:3,:4] = X.T
717  intrinsic_buffer[3:,:3] = np.eye(3)
718  intrinsic_buffer[3:,3] = gyro_bais
719 
720  # intrinsic_buffer = ((np.array(range(24),np.float32)+1)/10).reshape([6,4])
721 
722  imu_calib_table = get_IMU_Calib_Table(intrinsic_buffer, product_line)
723 
724  with open(os.path.join(directory,"calibration.bin"), 'wb') as outfile:
725  outfile.write(imu_calib_table.astype('f').tostring())
726 
727  is_write = input('Would you like to write the results to the camera? (Y/N)')
728  is_write = 'Y' in is_write.upper()
729  if is_write:
730  print('Writing calibration to device.')
731 
732  if product_line == 'L500':
733  l500_send_command(dev, WRITE_TABLE, 0, 0, 0, 0, imu_calib_table)
734  else:
735  calibration_table = get_calibration_table(imu_calib_table)
736  eeprom = get_eeprom(calibration_table)
737  write_eeprom_to_camera(eeprom, serial_no)
738 
739  print('Done.')
740  else:
741  print('Abort writing to device')
742 
743  except Exception as e:
744  print ('\nError: %s' % e)
745  finally:
746  if os.name == 'posix' and old_settings is not None:
747  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)
748 
749  """
750  wtw = dot(transpose(w),w)
751  wtwi = np.linalg.inv(wtw)
752  print(wtwi)
753  X = dot(wtwi, Y)
754  print(X)
755  """
756 if __name__ == '__main__':
757  main()
def get_calibration_table(d435_imu_calib_table)
std::string join(const std::string &base, const std::string &path)
Definition: filesystem.h:113
def get_IMU_Calib_Table(X, product_line)
std::vector< uint32_t > split(const std::string &s, char delim)
def wait_for_rs_device(serial_no)
def __init__(self, version, table_type)
def write_eeprom_to_camera(eeprom, serial_no='')
def get_measurements(self, buckets, bucket_labels)
def get_eeprom(calibration_table)
def get_debug_device(serial_no)
def l500_send_command(dev, op_code, param1=0, param2=0, param3=0, param4=0, data=[], retries=1)
def bytes_to_uint(bytes_array, order='little')
static std::string print(const transformation &tf)
def check_X(X, accel, show_graph)
def int_to_bytes(num, length=4, order='big')
def enable_imu_device(self, serial_no)
static rs2::device get_device()


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40