Maya Archaeology VR - Project for CSE 237D Course Spring 2022
This repository contains the code for data recording, visual-inertial SLAM, and dense reconstruction. The VR part of this project can be found in the main repository on GitLab.
An example collected RGB-D sequence can be view in the video below.
The reconstructed mesh with 5 mm TSDF voxel resolution and camera pose refinement is shown below.
- Kolin Guo
- Shrutheesh Iyer
- Tommy Sharkey
The steps are mainly summaries taken from
Intel D435i IMU Calibration Guide
and their official RealSense SDK.
If there is anything unclear or any software change occur, refer to them for
any updates.
Our calibration results are included in d435i_imu_calibration/.
Detailed steps to perform IMU calibration of D435i on Ubuntu
Prerequisites: Ubuntu >= 18.04, Python 3 (pip, numpy)
- Step 1: Install Intel RealSense SDK
pyrealsense2
wrapper:sudo pip3 install pyrealsense2
- Step 2: Clone Intel RealSense SDK:
git clone https://github.com/IntelRealSense/librealsense.git
- Step 3: Run
librealsense/tools/rs-imu-calibration/rs-imu-calibration.py
with sudo to perform IMU calibration. Check this README.md for more information.cd librealsense/tools/rs-imu-calibration sudo python3 rs-imu-calibration.py
- Step 4: At the end of the calibration script, select to write the results to D435i's eeprom.
Note that if you are connected to a laptop, your screen might rotate according to the connected D435i orientation. This is because the OS sees the IMU inside D435i as any IMU inside a tablet and thus will rotate screen orientation following it. To turn screen rotation off, see this post.
The steps to run the entire system are:
- Pull the docker images and build the containers with
./docker_setup.sh <container-name>
.
Alternatively, run./docker_setup.sh <container-name> -l
to build docker images locally from the Dockerfiles.
When building the container for the first time, copy and run the "Command to compile" in the login banner. - Open camera using
./realsense_capture/start_camera.sh
fromrealsense_capture
container. - Start tracking using
./slam_algorithms/maplab/run_maplab.sh <bag-name>
frommaplab
container. - Stop tracking by pressing
<ctrl-c>
and stopping the containers. - Reconstruct 3D mesh by running the following python script inside
maya_recon
container.python3 /maya-slam/scene_recon/open3d_tsdf/open3d_tsdf_reconstruction.py <bag-path> --voxel-length <voxel-length> --pose-refine
- Split mesh into chunks by running the following python script inside
maya_recon
container.python3 /maya-slam/scene_recon/split_mesh_into_json.py <ply-path> --box-size <box-size>
Some helpful scripts for visualization (all of them should be run inside maya_recon
container):
- Convert a rosbag to an MP4 video with RGB and depth images:
python3 /maya-slam/tools/rosbag_to_video.py <bag-path>
- Visualize PLY meshes or the split meshes
(supports up to 4 meshes at the same time,
usage examples can be found in the python script
visualize_mesh.py):
python3 /maya-slam/tools/visualize_mesh.py <ply-path>...
Camera Capture: realsense_capture
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/realsense:v1.0 | docker/Dockerfile_realsense | 1-2 minutes |
Container for launching and configuring the Intel RealSense D435i RGBD camera.
This docker image has Ubuntu 18.04, CUDA 11.3.1, ROS Melodic, OpenCV 4.4.0,
librealsense,
realsense-ros.
./docker_setup.sh realsense_capture
to pull the docker image and build the container.cd realsense_capture && ./build_ros.sh
to compile the packages.
Run ./realsense_capture/start_camera.sh
to start the camera.
This will launch the launch file
realsense_d435i_rviz.launch.
It is configured to launch the RGB color feed (1280x720 @ 30 fps),
depth feed (848x480 @ 30 fps) aligned with color using
HighAccuracyPreset,
and the IMU sensors (accel and gyro @ 200 fps).
To obtain better performance of the D435i depth camera, we followed the post of RealSense D400 series visual presets and uses the HighAccuracyPreset. All presets can be found here. For the best performance, please check out the advanced guide for tuning depth cameras.
Visual-Inertial SLAM #1: maplab
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/maplab:v1.0 | docker/Dockerfile_maplab | 35-45 minutes |
Container for launching and configuring maplab,
which is a visual-inertial SLAM supporting RGB-D+IMU mapping.
This docker image has Ubuntu 18.04, CUDA 11.3.1, ROS Melodic, OpenCV 4.4.0,
librealsense,
realsense-ros.
./docker_setup.sh maplab
to pull the docker image and build the container.cd slam_algorithms/maplab && ./build_ros.sh
to compile the packages.
Run ./slam_algorithms/maplab/run_maplab.sh <bag-name>
to start the camera tracking.
It accepts a <bag-name>
argument which will record and save the rosbag as
/maya-slam/slam_algorithms/rosbags/d435i_{bag-name}_{TIMESTAMP}.bag
The script will launch the launch file realsense.launch. It will run maplab by calling run_realsense, display the trajectory in RVIZ and also record color/depth/imu/camera pose trajectory generated by maplab as topics into a rosbag. The RealSense camera parameters can be modified in realsense-camera.yaml and realsense-imu.yaml.
π£ Remember to update the camera parameters for your RealSense camera
Visual-Inertial SLAM #2: orbslam3
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/orbslam3:v1.0 | docker/Dockerfile_orbslam3 | 5-6 minutes |
Container for launching and configuring
ORB-SLAM3, the state-of-the-art
ORB-feature-based visual-inertial SLAM algorithm on stereo+IMU system.
This docker image has Ubuntu 18.04, CUDA 11.3.1, ROS Melodic, OpenCV 4.4.0,
librealsense,
realsense-ros,
Python 3.6.9 with Jupyter Notebook.
Unfortunately, for RGB-D+IMU systems such as the RealSense D435i, ORB-SLAM3 does not have great performance and can sometimes lose track in featureless areas according to our experiments.
./docker_setup.sh orbslam3
to pull the docker image and build the container.cd slam_algorithms/ORB_SLAM3 && ./build.sh && ./build_ros.sh
to compile the packages.
Run roslaunch ORB_SLAM3 rgbd_d435i.launch
to launch tracking along with
RealSense camera.
The trajectory is written as
/maya-slam/slam_algorithms/ORB_SLAM3/Examples_old/ROS/ORB_SLAM3/FrameTrajectory.txt
A Jupyter notebook Fix_ORBSLAM3_Lose_Track.ipynb is included to fix any tracking loss in the ORB-SLAM3 camera pose trajectory by performing a consecutive frame multi-scale ICP of the two frames before and after losing track. Although not included yet, rosbag generation from the predicted camera pose trajectory can be easily written, enabling mesh reconstruction.
β ORB-SLAM3 has not been tested extensively for the project and we recommend using maplab for SLAM
Running ORB-SLAM3 on SLAM Datasets
Please place all datasets in slam_algorithms/datasets/
For TUM_VI,
ORB-SLAM3 expects the data in raw format (i.e., Euroc / DSO 512x512 dataset)
instead of rosbags.
datasets
βββ TUM_VI
βΒ Β βββ dataset-corridor1_512_16
β βΒ Β βββ dso
β βΒ Β βΒ Β βββ cam0
β βΒ Β βΒ Β βββ cam1
β βΒ Β βΒ Β βββ camchain.yaml
β βΒ Β βΒ Β βββ gt_imu.csv
β βΒ Β βΒ Β βββ imu_config.yaml
β βΒ Β βΒ Β βββ imu.txt
β βΒ Β βββ mav0
β βΒ Β βββ cam0
β βΒ Β βΒ Β βββ data
β βΒ Β βΒ Β βββ data.csv
β βΒ Β βββ cam1
β βΒ Β βΒ Β βββ data
β βΒ Β βΒ Β βββ data.csv
β βΒ Β βββ imu0
β βΒ Β βΒ Β βββ data.csv
β βΒ Β βββ mocap0
β βΒ Β βββ data.csv
βΒ Β Β βββ ...
βββ EuRoC
Use tum_vi_examples.sh
to run with TUM_VI dataset.
(Note: the seg fault at the end is not an issue since it only happens during destruction.)
Convert Rosbag to MP4 Video: maya_recon
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/maya_recon:v1.0 | docker/Dockerfile_maya_recon | No need to compile |
Container for converting a rosbag to an MP4 video with RGB and depth images.
Uses PIL and OpenCV for image editing and video generation.
Utilizes the custom ImageHelper class for
combining images and adding texts.
This docker image has Ubuntu 20.04, CUDA 11.3.1, ROS Noetic, OpenCV 4.2.0,
Python 3.8.10 with Jupyter Notebook and requirements.txt.
./docker_setup.sh maya_recon
to pull the docker image and build the container.
Run the following python script to convert the rosbag at <bag-path>
into
an MP4 video. The generated video is saved as
{bag-path}_bag_frames/{bag-name}_bag_frames.mp4
python3 ./tools/rosbag_to_video.py <bag-path>
Dense Reconstruction #1: maya_recon
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/maya_recon:v1.0 | docker/Dockerfile_maya_recon | No need to compile |
Container for dense 3D mesh reconstruction from RGB-D observations and the estimated camera pose trajectory.
Uses Open3D
ScalableTSDFVolume
to reconstruct the scene. Supports adding a consecutive frame camera pose refinement step
to improve the estimated camera poses. The pose refinement is based on
multi-scale ICP.
This docker image has Ubuntu 20.04, CUDA 11.3.1, ROS Noetic, OpenCV 4.2.0,
Python 3.8.10 with Jupyter Notebook and requirements.txt.
./docker_setup.sh maya_recon
to pull the docker image and build the container.
Run the following python script to perform 3D reconstruction from the rosbag
(with the estimated camera pose recorded in /tf
topic from map
frame to imu
frame)
at <bag-path>
. The generated PLY mesh is saved as
/maya-slam/scene_recon/output_plys/{bag-name}_o3dTSDF{voxel-length}m.ply
python3 ./scene_recon/open3d_tsdf/open3d_tsdf_reconstruction.py <bag-path> --voxel-length <voxel-length> --pose-refine
The TSDF <voxel-length>
is specified in meters and should be tuned given the available
system RAM resources (i.e., a smaller <voxel-length>
gives more detailed geometries
but requires more RAM resources).
If the option --pose-refine
is specified, perform the additional pose refinement step
and save the refined pose trajectory in output_plys/{ply-name}_pose
directory.
The pose_trajectory.html
inside the directory shows the camera pose trajectory
visualizations for the SLAM estimate and the refined trajectory.
β‘ We recommend running this dense reconstruction on a powerful system with >64GB RAM β‘
Some Jupyter Notebooks Containing Draft Code
Some Jupyter notebooks containing draft code are included in scene_recon/notebooks.
- Open3D_Dense_RGBD_SLAM.ipynb: scene reconstruction using Open3D tensor-based Dense RGBD SLAM. Probably due to the unstable implementation of the marching-cubes algorithm, the algorithm will always crashes the kernel during extracting the triangular mesh from the VoxelBlockGrid.
- Open3D_TSDF_integration.ipynb: draft code for open3d_tsdf_reconstruction.py.
- Open3D_TSDF_integration_tensor.ipynb: scene reconstruction using Open3D tensor-based VoxelBlockGrid. Probably due to the unstable implementation of the marching-cubes algorithm, the algorithm will always crashes the kernel during extracting the triangular mesh.
- PLY_vertex_color_to_face_color.ipynb: code for converting mesh per-vertex color information to per-face color information using PolyData.point_data_to_cell_data(). Not needed for this project.
- Split_scene_and_json_generation.ipynb: draft code for split_mesh_into_json.py.
Dense Reconstruction #2: openchisel
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/openchisel:v1.0 | docker/Dockerfile_openchisel | 1-2 minutes |
Container for dense 3D mesh reconstruction from RGB-D observations and the estimated camera pose trajectory.
Uses OpenChisel
to reconstruct the scene.
This docker image has Ubuntu 18.04, CUDA 11.3.1, ROS Melodic,
ros-melodic-pcl-ros.
./docker_setup.sh openchisel
to pull the docker image and build the container.cd scene_recon/openchisel && ./build_ros.sh
to compile the packages.
Run ./scene_recon/openchisel/run_openchisel.sh <bag-path>
to start the reconstruction from the rosbag
(with the estimated camera pose recorded in /tf
topic from map
frame to imu
frame)
at <bag-path>
. The generated PLY mesh is saved as
/maya-slam/scene_recon/output_plys/{bag-name}_openchisel.ply
The script will launch the launch file
launch_realsense_maplab.launch.
The TSDF <voxel_resolution_m>
parameter is specified in meters and can be tuned given the available
system RAM resources. However, OpenChisel seems to not function properly
when <voxel_resolution_m>
is below 0.04 meter (i.e., 4 cm), presumably due to suboptimal implementation.
π£ We recommend using the Open3D-based maya_recon for dense reconstruction
Split Mesh into Chunks: maya_recon
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/maya_recon:v1.0 | docker/Dockerfile_maya_recon | No need to compile |
Container for splitting mesh into chunks and generating the JSON configuration file
to speedup mesh loading and manipulation.
Uses PyVista
PolyData.clip_box()
function to clip the meshes.
Other 3D mesh processing libraries have not yet correctly implemented
texture interpolation during mesh clipping
(e.g., trimesh issue #1313,
Open3D issue #2464).
This docker image has Ubuntu 20.04, CUDA 11.3.1, ROS Noetic, OpenCV 4.2.0,
Python 3.8.10 with Jupyter Notebook and requirements.txt.
./docker_setup.sh maya_recon
to pull the docker image and build the container.
Run the following python script to split the mesh at <ply-path>
into chunks
and generate a JSON configuration file.
The <box-size>
is the chunk side length specified in meters
and should be tuned to balance the chunk PLY filesize and the number of split mesh chunks
to achieve the optimal mesh loading speed.
python3 ./scene_recon/split_mesh_into_json.py <ply-path> --box-size <box-size>
The generated files are saved in
/maya-slam/scene_recon/output_plys/{ply-name}_split
directory.
An example folder structure is shown below
output_plys
βββ d435i_kitchen_2022-06-04-23-39-35_o3dTSDF0.005m_pose_refined.ply
βββ d435i_kitchen_2022-06-04-23-39-35_o3dTSDF0.005m_pose_refined_split
βΒ Β βββ meshes
β βΒ Β βββ chunk_(0,0,0).ply
β βΒ Β βββ chunk_(0,1,0).ply
β βΒ Β βββ chunk_(-1,-1,0).ply
β βΒ Β βββ chunk_(1,0,0).ply
β βΒ Β βββ ...
βΒ Β Β βββ config.json
βββ ...
β‘ We recommend running this mesh splitting on a powerful system with 32GB RAM β‘
Visualize Meshes: maya_recon
docker image | Dockerfile | Estimated compile time |
---|---|---|
kolinguo/maya_recon:v1.0 | docker/Dockerfile_maya_recon | No need to compile |
Container for visualizing PLY meshes or the split mesh chunks.
Uses PyVista to load and visualize the meshes
due to its great efficiency of processing very large meshes
compared to other 3D mesh processing libraries (e.g., trimesh and Open3D).
This docker image has Ubuntu 20.04, CUDA 11.3.1, ROS Noetic, OpenCV 4.2.0,
Python 3.8.10 with Jupyter Notebook and requirements.txt.
./docker_setup.sh maya_recon
to pull the docker image and build the container.
Run the following python script to visualize the mesh or the split mesh chunks
at <ply-path>
(supports up to 4 meshes at the same time,
usage examples can be found in the python script
visualize_mesh.py):
python3 ./tools/visualize_mesh.py <ply-path>...
You can check out our video description below and our final report here.