2 from __future__
import print_function
10 import pyrealsense2
as rs
21 L515_FW_VER_REQUIRED =
'01.04.01.00' 25 if os.name ==
'posix':
30 is_data =
lambda : select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], [])
31 get_key =
lambda : sys.stdin.read(1)
35 is_data = msvcrt.kbhit
36 get_key =
lambda : msvcrt.getch()
39 raise Exception(
'Unsupported OS: %s' % os.name)
41 if sys.version_info[0] < 3:
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]
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" 59 res = bytearray(length)
60 for i
in range(length):
64 raise OverflowError(
"Number {} doesn't fit into {} bytes.".format(num, length))
71 bytes_array = list(bytes_array)
74 return struct.unpack(
'>i', struct.pack(
'BBBB', *([0] * (4 - len(bytes_array))) + bytes_array))[0] & 0xffffffff
76 return struct.unpack(
'>i', struct.pack(
'BBBB', *([0] * (4 - len(bytes_array))) + bytes_array))[0] & 0xffffffff
100 self.
max_norm = np.linalg.norm(np.array([0.5, 0.5, 0.5]))
106 self.thread.acquire()
107 self.
status = self.Status.idle
110 self.thread.release()
124 if self.
status == self.Status.idle:
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])
132 if self.
status == self.Status.collect_data:
133 sys.stdout.write(
'\r %15s' % self.
status)
138 if pr.stream_type() == rs.stream.gyro:
139 self.collected_data_gyro.append(np.append(frame.get_timestamp(), data_np))
144 self.collected_data_accel.append(np.append(frame.get_timestamp(), data_np))
149 sys.stdout.write(color)
151 sys.stdout.write(COLOR_RESET)
154 print(
'WARNING: MOVING')
155 self.
status = self.Status.rotate
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
165 self.thread.release()
168 if pr.stream_type() == rs.stream.gyro:
170 sys.stdout.write(
'\r %15s' % self.
status)
171 crnt_dir = np.array(data_np) / np.linalg.norm(data_np)
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)))
180 self.
status = self.Status.wait_to_stable
181 sys.stdout.write(
'\r'+
' '*90)
186 if self.
status == self.Status.wait_to_stable:
187 sys.stdout.write(
': %-3.1f (secs)' % (self.
time_to_stable - elapsed_time))
189 self.
status = self.Status.rotate
194 self.
status = self.Status.collect_data
198 except Exception
as e:
200 self.thread.acquire()
201 self.
status = self.Status.idle
203 self.thread.release()
207 print(
'-------------------------')
208 print(
'*** Press ESC to Quit ***')
209 print(
'-------------------------')
210 for bucket,bucket_label
in zip(buckets, bucket_labels):
214 self.
status = self.Status.rotate
215 self.thread.acquire()
216 while (
not self.
is_done and self.
status != self.Status.idle):
219 raise Exception(
'No IMU data. Check connectivity.')
221 raise Exception(
'User Abort.')
228 cfg.enable_device(serial_no)
230 self.pipeline.start(cfg)
231 except Exception
as e:
236 active_imu_profiles = []
238 active_profiles = dict()
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
245 if pr.stream_type() == rs.stream.accel
and pr.format() == rs.format.motion_xyz32f:
246 active_profiles[pr.stream_type()] = pr
251 print(
'No IMU sensor found.')
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.')
258 self.imu_sensor.stop()
259 self.imu_sensor.close()
260 self.imu_sensor.open(active_imu_profiles)
265 if self.imu_sensor.supports(rs.option.enable_motion_correction):
266 self.imu_sensor.set_option(rs.option.enable_motion_correction, 0)
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)
281 self.buffer.dtype=np.uint32
285 self.buffer.dtype=np.uint32
286 self.
buffer[3] = crc32 % (1<<32)
289 self.buffer.dtype=np.uint8
294 return struct.unpack(
'f', struct.pack(
'i', ival))[0]
297 return struct.unpack(
'i', struct.pack(
'f', fval))[0]
303 buffer.dtype=np.uint32
304 tab1_size = buffer[3]
305 buffer.dtype=np.uint8
306 print(
'tab1_size (all_data): ', tab1_size)
308 tab1 = buffer[cmd_size:cmd_size+tab1_size]
312 print(
'tab2_size (calibration_table): ', tab2_size)
314 tab2 = tab1[header_size:header_size+tab2_size]
318 print(
'tab3_size (calibration_table): ', tab3_size)
320 tab3 = tab2[header_size:header_size+tab3_size]
324 print(
'tab4_size (D435_IMU_Calib_Table): ', tab4_size)
326 tab4 = tab3[header_size:header_size+tab4_size]
327 return tab1, tab2, tab3, tab4
330 version = [
'0x02',
'0x01']
333 if product_line ==
'L500':
334 version = [
'0x05',
'0x01']
337 header =
CHeader(version, table_type)
339 header_size = header.size()
340 data_size = 37*4 + 96
341 size_of_buffer = header_size + data_size
342 assert(size_of_buffer % 4 == 0)
343 buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
345 use_extrinsics =
False 346 use_intrinsics =
True 348 data_buffer = np.ones(data_size, dtype=np.uint8) * 255
349 data_buffer.dtype = np.float32
352 np.int32(int(use_extrinsics)))
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]
360 data_buffer[13:13+X.size] = intrinsic_vector
361 data_buffer.dtype = np.uint8
363 header.set_data_size(data_size)
365 header.set_crc32(binascii.crc32(data_buffer))
366 buffer[:header_size] = header.get_buffer()
367 buffer[header_size:] = data_buffer
372 version = [
'0x02',
'0x00']
375 header =
CHeader(version, table_type)
377 d435_imu_calib_table_size = d435_imu_calib_table.size
379 data_size = d435_imu_calib_table_size + sn_table_size
381 header_size = header.size()
382 size_of_buffer = header_size + data_size
383 assert(size_of_buffer % 4 == 0)
384 buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
386 data_buffer = np.ones(data_size, dtype=np.uint8) * 255
387 data_buffer[:d435_imu_calib_table_size] = d435_imu_calib_table
389 header.set_data_size(data_size)
390 header.set_crc32(binascii.crc32(data_buffer))
392 buffer[:header_size] = header.get_buffer()
393 buffer[header_size:header_size+data_size] = data_buffer
397 version = [
'0x01',
'0x01']
400 header =
CHeader(version, table_type)
402 DC_MM_EEPROM_SIZE = 520
405 header_size = header.size()
406 size_of_buffer = DC_MM_EEPROM_SIZE
407 data_size = size_of_buffer - header_size
410 assert(size_of_buffer % 4 == 0)
411 buffer = np.ones(size_of_buffer, dtype=np.uint8) * 255
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:]))
417 buffer[:header_size] = header.get_buffer()
423 DC_MM_EEPROM_SIZE = eeprom.size
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' 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
438 buffer[:len(cmd)] = cmd
439 buffer[len(cmd):len(cmd)+eeprom.size] = eeprom
443 print(
'Error getting RealSense Device.')
447 rcvBuf = debug.send_and_receive_raw_data(bytearray(buffer))
448 if rcvBuf[0] == buffer[4]:
449 print(
'SUCCESS: saved calibration to camera.')
451 print(
'FAILED: failed to save calibration to camera.')
457 devices = ctx.query_devices()
460 if len(serial_no) == 0
or serial_no == dev.get_info(rs.camera_info.serial_number):
464 print(
'No RealSense device found' +
str(
'.' if len(serial_no) == 0
else ' with serial number: '+serial_no))
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)
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)
481 pylab.plot(norm_data,
'.b')
483 pylab.plot(norm_fdata,
'.g')
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)
488 def l500_send_command(dev, op_code, param1=0, param2=0, param3=0, param4=0, data=[], retries=1):
490 for i
in range(retries):
492 debug_device = rs.debug_protocol(dev)
493 gvd_command_length = 0x14 + len(data)
507 buf += bytearray(data)
509 res = debug_device.send_and_receive_raw_data(buf)
511 if res[0] == op_code:
515 raise Exception(
"send_command return error", res[0])
525 start = int(round(time.time() * 1000))
526 now = int(round(time.time() * 1000))
528 while now - start < 5000:
529 devices = ctx.query_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):
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))
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))
548 if any([help_str
in sys.argv
for help_str
in [
'-h',
'--help',
'/?']]):
549 print(
"Usage:", sys.argv[0],
"[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.')
556 print(
'If -i option is given, calibration is done using previosly saved files')
557 print(
'Otherwise, an interactive process is followed.')
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]
573 print(
'waiting for realsense device...')
577 product_line = dev.get_info(rs.camera_info.product_line)
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.")
585 print(
' firmware ' + fw_version +
' passed check.')
587 buckets = [[0, -g, 0], [ g, 0, 0],
588 [0, g, 0], [-g, 0, 0],
589 [0, 0, -g], [ 0, 0, g]]
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"]
602 gyro_bais = np.zeros(3, np.float32)
609 gyro = np.loadtxt(gyro_file, delimiter=
",")
610 gyro = gyro[gyro[:, 0] < gyro[0, 0]+4000, :]
612 gyro_bais = np.mean(gyro[:, 1:], axis=0)
616 max_norm = np.linalg.norm(np.array([0.5, 0.5, 0.5]))
618 measurements = [[], [], [], [], [], []]
620 with open(accel_file,
'r') as csvfile: 621 reader = csv.reader(csvfile) 624 M = np.array([float(row[1]), float(row[2]), float(row[3])])
626 for i
in range(0, len(buckets)):
627 if np.linalg.norm(M - buckets[i]) < max_norm:
629 measurements[i].append(M)
631 print(
'read %d rows.' % rnum)
633 print(
'Start interactive mode:')
634 if os.name ==
'posix':
635 old_settings = termios.tcgetattr(sys.stdin)
636 tty.setcbreak(sys.stdin.fileno())
639 if not imu.enable_imu_device(serial_no):
640 print(
'Failed to enable device.')
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)
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. >')
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')
656 print(
'Not writing to files.')
658 measurements = [mm[:,1:]
for mm
in measurements]
660 gyro_bais = np.mean(gyro[:, 1:], axis=0)
663 mlen = np.array([len(meas)
for meas
in measurements])
665 print(
'using %d measurements.' % mlen.sum())
668 w = np.zeros([nrows, 4])
669 Y = np.zeros([nrows, 3])
671 for i
in range(0, len(buckets)):
672 for m
in measurements[i]:
677 Y[row, 0] = buckets[i][0]
678 Y[row, 1] = buckets[i][1]
679 Y[row, 2] = buckets[i][2]
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)
686 print(
"residuals:", residuals)
688 print(
"singular:", singular)
689 check_X(X, w[:,:3], show_graph)
693 if product_line ==
'L500':
694 calibration[
"device_type"] =
"L515" 696 calibration[
"device_type"] =
"D435i" 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)
708 directory = os.path.dirname(accel_file)
if accel_file
else '.' 710 with open(os.path.join(directory,
"calibration.json"),
'w')
as outfile:
711 outfile.write(json_data)
714 intrinsic_buffer = np.zeros([6,4])
716 intrinsic_buffer[:3,:4] = X.T
717 intrinsic_buffer[3:,:3] = np.eye(3)
718 intrinsic_buffer[3:,3] = gyro_bais
724 with open(os.path.join(directory,
"calibration.bin"),
'wb')
as outfile:
725 outfile.write(imu_calib_table.astype(
'f').tostring())
727 is_write = input(
'Would you like to write the results to the camera? (Y/N)')
728 is_write =
'Y' in is_write.upper()
730 print(
'Writing calibration to device.')
732 if product_line ==
'L500':
741 print(
'Abort writing to device')
743 except Exception
as e:
744 print (
'\nError: %s' % e)
746 if os.name ==
'posix' and old_settings
is not None:
747 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)
750 wtw = dot(transpose(w),w) 751 wtwi = np.linalg.inv(wtw) 756 if __name__ ==
'__main__':
def get_calibration_table(d435_imu_calib_table)
def imu_callback(self, frame)
std::string join(const std::string &base, const std::string &path)
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 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 bitwise_int_to_float(ival)
status
Status.collect_data.
def bytes_to_uint(bytes_array, order='little')
static std::string print(const transformation &tf)
def bitwise_float_to_int(fval)
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()