The project was tested using:
- Ubuntu 18.06
- ROS Melodic Morenia
- STM32CubeIDE for Linux
MCU-platform with built-in programmer | STM32F4DISCOVERY |
IMU | MPU-9150 |
UART-to-USB stick | any, we used stick based on CP2102 stone |
3.5 mm mono (stereo, tri) jack connector with cable for depth camera triggering | any |
The STM32 MCU-platform is chosen as it meets all the requirements described in the SmartDepthSync paper. The IMU is fed by external MCU reference clock for data rate stability.
The MCU firmware aimed on IMU-data gathering and Azure Kinect DK depth camera time synchronization. It is developed using STM32CubeIDE for Linux. The main source code is placed in main.c while the other setups are stored in synchro.ioc and setup through the IDE GUI. It means there is no need to edit other source files except two mentioned.
The MCU outputs IMU data as are plain ASCII strings that can be used independently on ROS and may be parsed by another data recording/processing API. These strings contain timestamp (minutes, seconds, subseconds (1/25600000 of second) and IMU data (3D-angular velocity, temperature, 3D-acceleration) with format:
"i0%02x %02x %04x %04x %04x %04x %04x %04x %04x %04x %04x %04x\n"
\/\__/ \__/ \__/ \_______/ \____________/ \__/ \____________/
| hour mins secs subsecs 3D gyro temp 3D acc
IMU 0 identifier for compatibility with other projects
"c0%02x %02x %04x %04x %04x\n"
\/\__/ \__/ \__/ \_______/
| hour mins secs subsecs
Camera 0 identifier for compatibility with other projects
The software consists of ROS drivers for handling depth image and IMU data and precise timestamping.
Lidar ROS driver is based on common ROS package with our patch for precise timestamping.
IMU ROS driver is developed from scratch and produces sensor_msgs/Imu messages.
Any question — raise an issue, please.
MCU pin | Name | Role |
PB6 | I2C1_SCL | I2C SCL line for IMU module data transfer |
PB7 | I2C1_SDA | I2C SDA line for IMU module data transfer |
PC9 | GPIO_EXTI9 | Interrupt input pin from IMU module. IMU trigger this pin when new data sample is ready |
PC10 | RCC_OSC_OUT | UART Transmit IMU data and depth camera timestamps data line to PC through UART-to-USB stick |
PC11 | TIM5_CH1 | UART Receive phase alignment commands line from PC through UART-to-USB stick |
PA5 | TIM2_CH1 | Depth camera triggering output pin |
PA6 | TIM3_CH1 | IMU sensor 19.2 MHz reference clock output pin |
Using this materials please do not forget to reference this repository and cite the paper:
@article{faizullin2022smartdepthsync,
author={Faizullin, Marsel and Kornilova, Anastasiia and Akhmetyanov, Azat and Pakulev, Konstantin and Sadkov, Andrey and Ferrer, Gonzalo},
title={SmartDepthSync: Open Source Synchronized Video Recording System of Smartphone RGB and Depth Camera Range Image Frames with Sub-millisecond Precision},
journal={IEEE Sensors Journal},
publisher={IEEE},
year={2022},
volume={},
number={},
pages={1-1},
doi={10.1109/JSEN.2022.3150973}
}