---
tags: ITRI, VIO, Instruction
---
# Kalibr and Maplab Tutorial
這個筆記將說明如何使用Kalibr進行相機和IMU的校正, 並使用maplab利用相機和IMU的資料建立地圖和定位
## 0. 目錄
1. Kalibr ([Github Wiki Page](https://github.com/ethz-asl/kalibr/wiki "Kalibr github wiki"))
a. 簡介
b. 安裝 kalibr
c. 安裝 usb_cam
d. 安裝 xsens driver
e. 相機校正流程
f. IMU校正
g. 相機-IMU校正流程
h. Tips
2. Maplab ([Github Wiki Page](https://github.com/ethz-asl/maplab/wiki "Maplab github wiki"))
a. 簡介
b. 安裝
c. 介面說明
d. 建立地圖
e. 地圖定位
## 1. Kalibr
### a. 簡介

---
Kalibr是一個解決以下校準問題的工具箱:
1. **多攝像機校準:** 具有非全局共享重疊視野的攝像機系統的內在和外在校準。
2. **相機-IMU校準:** IMU-相機系統的校準。
### b. 安裝 ([Reference](https://github.com/ethz-asl/kalibr/wiki/installation))
#### 1. 安裝ROS
請到[ros.org](http://www.ros.org/)以獲得詳細的安裝資訊
#### 2. 下載和安裝相關套件
```
sudo apt-get install python-setuptools python-rosinstall ipython libeigen3-dev libboost-all-dev doxygen libopencv-dev ros-indigo-vision-opencv ros-indigo-image-transport-plugins ros-indigo-cmake-modules python-software-properties software-properties-common libpoco-dev python-matplotlib python-scipy python-git python-pip ipython libtbb-dev libblas-dev liblapack-dev python-catkin-tools libv4l-dev
sudo pip install python-igraph --upgrade
```
#### 3. 建立 catkin workspace
```
mkdir -p ~/kalibr_workspace/src
cd ~/kalibr_workspace
source /opt/ros/kinetic/setup.bash
catkin init
catkin config --extend /opt/ros/kinetic
catkin config --merge-devel # Necessary for catkin_tools >= 0.4. catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
```
#### 4. 將專案下載到 workspace
```
cd ~/kalibr_workspace/src
git clone https://github.com/ethz-asl/Kalibr.git
```
#### 5. 建置專案
建制完畢後, 記得要 souce 剛剛建置的 workspace 的 setup file, 才能使用 Kalibr (記得每次開啟一個新的terminal都要執行)
```
cd ~/kalibr_workspace
catkin build -DCMAKE_BUILD_TYPE=Release -j4
source ~/kalibr_workspace/devel/setup.bash
```
### c. 安裝 usb_cam
usb_cam 是 ROS 提供的套件, 可以驅動標準 USB Camera, 並以sensor_msgs::Image的資料格式 publish 影像資訊。
#### 1. 下載&建置套件
首先建立一個新的 workspace
```
source /opt/ros/kinetic/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/
catkin_make
source devel/setup.bash
```
接著從 github 下載套件
```
cd ~/catkin_ws/src
git clone https://github.com/bosch-ros-pkg/usb_cam.git
```
下載完成後, 建置專案
```
cd ~/catkin_ws/
catkin_make
```
#### 2. 插入裝置
插入USB camera裝置, 輸入以下指令並確認出現的裝置名稱。 若是使用筆電,通常 video0 是筆電本身的相機鏡頭。
```
cd /dev && find . -name "video*"
```

#### 3. 修改 launch 檔
到 usb_cam 底下的 launch 資料夾可以看到它說提供的範例 launch 檔。記得將video_device改成你電腦上相機裝置的名稱。
為了可以調整相機的framerate加入下列指令:
```xml=9
<param name="framerate" value="5" />
```
修改後的檔案如下:
```xml=
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="framerate" value="5" />
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_raw"/>
<param name="autosize" value="true" />
</node>
</launch>
```
其中 image_view 的 node 是用來顯示擷取到的影像資料,不影響usb_cam的本身的執行。
### d. 安裝xsens driver
#### 1. 下載和安裝
請到這個[github page](https://github.com/xsens/xsens_mti_ros_node)去參照詳細安裝資訊。
#### 2. 啟動
到 xsens_driver 底下的 config 資料夾調整相關參數。主要會調整的是裝置名稱和odr(output data rate)
```yaml=1
# Serial device
device: /dev/ttyUSB0
```
```yaml=13
# Output data rate of device. Valid values: 1, 2, 4, 5, 10, 20, 40, 50, 80, 100, 200, 400, 800
# Refer to MT Low Level Communication Protocol Documentation for supported ODRs for each MTi series
# https://base.xsens.com/hc/en-us/articles/207003759-Online-links-to-manuals-from-the-MT-Software-Suite
odr: 200
```
### f. IMU校正
在進行imu-cam的校正之前需事先測量IMU的內部參數。 可使用[這個](https://github.com/gaowenliang/imu_utils?fbclid=IwAR2u30AnTzmKPmAn02-M_36a5PoQ0I0ByB9K5ms25DxI6VYyZxy5TiQcA5k)工具,需錄製2個小時的imu資料 bag 檔, 記得要收集到所有的資料(各軸加速度、 角速度)。
獲得參數後,按照下列格式建立一個 imu.yaml 檔。 其中 rostopic 為錄製的 bag 檔 imu 資料的名稱。
```yaml
accelerometer_noise_density: 1.2369e-02
accelerometer_random_walk: 5.3058e-04
gyroscope_noise_density: 8.7575e-03
gyroscope_random_walk: 7.252e-05
rostopic: /imu0 #the IMU ROS topic
update_rate: 200.0 #Hz (for discretization of the values above)
```
### g. 相機校正 ([Reference](https://github.com/ethz-asl/kalibr/wiki/multiple-camera-calibration))
#### 1. 建立launch檔
可以另外建立一個node來管理資料收集,或是直接在 usb_cam 的 launch 資料夾底下另外建立一個 launch 檔。 例如我們先建立一個叫做 cam_data_collect.launch 的檔案。
```xml=
<?xml version='1.0' ?>
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="framerate" value="5" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_mono"/>
<param name="autosize" value="true" />
</node>
<node pkg="rosbag" type="record" name="rosbag_record_camera" respawn="true" args="/cam0/image_raw">
<remap from="/cam0/image_raw" to="usb_cam/image_mono"/>
</node>
</launch>
```
在這裡我們呼叫了 rosbag 的 record 功能, 方便我們同時進行資料的接收和儲存。
```xml=20
<node pkg="rosbag" type="record" name="rosbag_record_camera" respawn="true" args="/cam0/image_raw">
<remap from="/cam0/image_raw" to="usb_cam/image_mono"/>
</node>
```
args 的值即為要儲存的topic名稱, 可以自行命名, 但按照此一格式對於後面校正會比較方便。
```
args="/cam0/image_raw
```
在這裡將原本 usb_cam 所 publish 的 topic 名稱 remap 成我們想要儲存成的名稱。注意這裡我們接收的是image_mono即灰階照片, 因為不論是kalibr或是maplab都不需要照片的彩色資訊(它們會自行把彩色照片轉成灰階照片),因此只儲存灰階資訊有效降低收集資料的檔案大小。
```xml
<remap from="/cam0/image_raw" to="usb_cam/image_mono"/>
```
#### 2. 錄製照片
將相機固定在光線充足的地方, 手持校正版並不斷改變位置和角度。範例影片[連結](https://www.youtube.com/watch?v=UxhOWRjkkbM)。
將錄製完的bag檔命名為 static.bag 。
#### 3. 準備校正板和校正板資料檔
需要先自行準備一個校正版,有數種不同型式的校正版可選擇,以下使用官方推薦的apriltag board進行講解。 詳細資料請至[這裡](https://github.com/ethz-asl/kalibr/wiki/calibration-targets)。
i.[下載](https://github.com/ethz-asl/kalibr/wiki/downloads)apriltag board並影印,貼在一個足夠硬的紙板上)
ii.建立一個 target.yaml 檔, 並編寫以下內容:
```
target_type: 'aprilgrid' #gridtype
tagCols: 6 #number of apriltags
tagRows: 6 #number of apriltags
tagSize: 0.088 #size of apriltag, edge to edge [m]
tagSpacing: 0.3 #ratio of space between tags to tagSize
```
$~~~$$~~~$ tagSpacing 是 tagsize 和 tag 之間距離的比例。 tagSize 和 tagSpacing需要依照實際印出來的大小計算和修改。

#### 4. 校正
要使用校正工具,需提供下列輸入:
* ——bag [filename.bag]
為步驟1收集到的照片資料。
* ——topics [TOPIC_0 ... TOPIC_N]
列出每一個裝置的照片資訊的topic名稱。
* ——models [MODEL_0 ... MODEL_N]
列出每一個裝置的相機模型以及失真模型, 裝置順序和 --topics 一樣。
* ——target [target.yaml]
為步驟2所產生的 .yaml 檔
創建一個資料夾, 將 static.bag 和 target.yaml 複製過去。打開terminal,先到kalibr所在的 workspace 去 source setup file, 再移動到剛剛的資料夾,在terminal輸入以下指令。 其中 --show-extraction 會顯示擷取照片的過程。
```
kalibr_calibrate_cameras --target target.yaml --bag static.bag --models pinhole-equi --topics /cam0/image_raw --show-extraction
```
#### 5. 結果
校正結束後會產生下列檔案:
* report-capd-[BAGNAME].pdf: pdf格式的結果報告, 包含各類圖表。
* results-cam-[BAGNAME].txt: txt格式的結果報告。
* camchain-[BAGNAME].yaml: yaml格式的結果報告, 會被用在接下來的相機-IMU的校正上。
### f. 相機-IMU校正 ([Reference](https://github.com/ethz-asl/kalibr/wiki/camera-imu-calibration))
#### 1. 建立launch file
先確定 workspace 裏面已經有 usb_cam 和 xsens_driver, xsens_msgs並成功編譯。
建議再建立一個package來管裡, 並在底下建立一個 launch 資料夾。
```
cd ~/catkin_ws/src
catkin_create_pkg imu_cam std_msgs rospy roscpp
cd imu_cam
mkdir launch
cd ~/catkin_ws
source devel/setup.bash
```
在 launch 資料夾裏面建立一個 data_collect.launch 檔案, 並編寫以下內容
```xml
<?xml version='1.0' ?>
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="framerate" value="20" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_ca
<param name="io_method" value="mmap"/>
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_mono"/>
<param name="autosize" value="true" />
</node>
<node name="xsens_mti" pkg="xsens_driver" type="mtnode.py">
<rosparam command="load" file="$(find xsens_driver)/config/xsens.yaml"/>
</node>
<node pkg="rosbag" type="record" name="rosbag_record_imu_camera" respawn="true" args="-o $(find imu_cam)/bags/imu-cam /cam0/image_raw /imu0">
<remap from="imu0" to="mti/sensor/imu"/>
<remap from="/cam0/image_raw" to="usb_cam/image_mono"/>
</node>
</launch>
```
錄製完的 bag 檔會被儲存在 imu_cam 底下的 bag 資料夾裡。
#### 2. 錄製資料
將校正版固定在光線充足的地方,啟動裝置後,將裝置旋轉、移動。 儘量避免振動,例如將裝置從靜止的地方拿起時。範例影片見[這裡](https://www.youtube.com/watch?v=puNXsnrYWTY&app=desktop)。
使用以下指令執行launch檔以啟動裝置和錄製bag檔,並將錄製完的 bag 檔命名為 dynamic.bag。
```
cd ~/catkin_ws/
roslaunch imu_cam data_collect.launch
```
#### 3. 校正
使用kalibr進行imu-cam的校正需要以下的輸入:
* ——bag filename.bag
包含 imu 和 camera資料的 bag 檔
* ——cam camchain.yaml
相機系統的內部和外部參數。相機校正產生的.yaml檔可以用在這裡。
* ——imu imu.yaml
包含 imu 內部參數的 .yaml 檔
* ——target target.yaml
包含校正板的資訊
建立一個資料夾, 將 dynamic.bag, imu.yaml, camchain.yaml 複製進去, 打開一個新的terminal, 先到 kalibr 所在的 workspace 裏面 source setup file, 再移動到剛剛的資料夾底下執行以下指令:
```
kalibr_calibrate_imu_camera --target apriltag.yaml --cam camchain.yaml --imu imu.yaml --bag dynamic.bag --show-extraction
```
若是想要讀取 bag 檔的指定時間範圍,可加入下面的參數。其中 5 和 35 是起始和結束的時間。
```
--bag-from-to 5 35
```
校正會花一段不短的時間(1~2小時),可以先去喝杯茶:)
#### 4. 結果
校正結束後會產生下列的檔案:
* report-imucam-[BAGNAME].pdf: pdf格式的結果報告, 包含各類圖表。
* results-imucam-[BAGNAME].txt: txt格式的結果報告。
* camchain-imucam-[BAGNAME].yaml: yaml格式的結果報告。 主要是輸入的camchain.yaml檔案上增加轉移矩陣和time shift資訊。 在後續maplab工具的會使用到裡面的校正結果。
### h. Tips
#### 1. 執行kalibr時顯示ImportError: cannot import name NavigationToolbar2Wx
參照[這篇issue](https://github.com/ethz-asl/kalibr/issues/202), 需修改**src/Kalibr/Schweizer-Messer/sm_python/python/sm/PlotCollection.py** 的 line 8:
```
from matplotlib.backends.backend_wxagg import NavigationToolbar2Wx as Toolbar
```
to
```
from matplotlib.backends.backend_wx import NavigationToolbar2Wx as Toolbar
```
#### 2. 檢查相機校正的結果
觀察結果報告的資料,檢查reprojection error。官方說明這個值應該為0.1~0.2, 若太大表示該次校正有問題。 另外也可以檢查distortion error,這個值雖然會因為選擇不同的model而有不同的表現,但應該有會是一個很小的值。建議可以先去[下載](https://github.com/ethz-asl/kalibr/wiki/downloads)他提供的範例dataset並操作一次校正,並參考校正結果的數據。
#### 3. 檢查imu-camera的校正結果
校正結果有一個值為timeshift_cam_imu, 表示 imu 資料和 camera 資料兩個資料流的時間差距。爬梳一些討論串後得知若這個值很大則代表 imu 和 camera之間存在同步問題,會很大的影響校正結果以及後續使用 maplab 時的表現。
注意 Kalibr 計算這個值並不是透過兩筆資料的timestamp做計算。其方法請參照以下源始碼的註解。
>#estimates the timeshift between the camearas and the imu using a crosscorrelation approach
>#approach: angular rates are constant on a fixed body independent of location
#using only the norm of the gyro outputs and assuming that the biases are small
#we can estimate the timeshift between the cameras and the imu by calculating
#the angular rates of the cameras by fitting a spline and evaluating the derivatives
#then computing the cross correlating between the "predicted" angular rates (camera)
#and imu, the maximum corresponds to the timeshift...
#in a next step we can use the time shift to estimate the rotation between camera and imu
此外,也可以檢查校正結果裏面imu-camera之間的旋轉矩陣,看是否合理。
## 2. Maplab
### a. 簡介

該專案包含maplab,為一個開放的、面向研究的視覺慣性映射框架。用C++編寫,用於創建、處理和操作多重地圖的合併, maplab可以被視為即用型視覺慣性映射和定位系統,提供了一系列多會話映射工具, 包括地圖合併, 視覺慣性批量優化和。
此外,它還包括一個在線前端ROVIOLI,它可以創建視覺慣性圖並跟踪定位圖中的全局無漂移姿勢。
### b. 安裝 ([Reference](https://github.com/ethz-asl/maplab/wiki/Installation-Ubuntu))
**1. 安裝相關套件**
```cmd
# Install ROS
export UBUNTU_VERSION=xenial #(Ubuntu 16.04: xenial, Ubuntu 14.04: trusty, Ubuntu 18.04: bionic)
export ROS_VERSION=kinetic #(Ubuntu 16.04: kinetic, Ubuntu 14.04: indigo, Ubuntu 18.04: melodic)
# NOTE: Follow the official ROS installation instructions for melodic.
sudo apt install software-properties-common
sudo add-apt-repository "deb http://packages.ros.org/ros/ubuntu $UBUNTU_VERSION main"
wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -O - | sudo apt-key add -
sudo apt update
sudo apt install ros-$ROS_VERSION-desktop-full "ros-$ROS_VERSION-tf2-*" "ros-$ROS_VERSION-camera-info-manager*" --yes
# Install framework dependencies.
# NOTE: clang-format-3.8 is not available anymore on bionic, install a newer version.
sudo apt install autotools-dev ccache doxygen dh-autoreconf git liblapack-dev libblas-dev libgtest-dev libreadline-dev libssh2-1-dev pylint clang-format-3.8 python-autopep8 python-catkin-tools python-pip python-git python-setuptools python-termcolor python-wstool libatlas3-base --yes
sudo pip install requests
```
**2. 更新ROS環境**
```cmd
sudo rosdep init
rosdep update
echo ". /opt/ros/$ROS_VERSION/setup.bash" >> ~/.bashrc
source ~/.bashrc
```
**3. 建立catkin workspace**
```cmd
export ROS_VERSION=kinetic #(Ubuntu 16.04: kinetic, Ubuntu 14.04: indigo)
export CATKIN_WS=~/maplab_ws
mkdir -p $CATKIN_WS/src
cd $CATKIN_WS
catkin init
catkin config --merge-devel # Necessary for catkin_tools >= 0.4.
catkin config --extend /opt/ros/$ROS_VERSION
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
cd src
```
**4. 下載maplab套件**
```cmd
git clone https://github.com/ethz-asl/maplab.git --recursive
git clone https://github.com/ethz-asl/maplab_dependencies --recursive
```
**5. 建置maplab**
```
cd $CATKIN_WS
catkin build maplab
```
這個階段會等一段時間,先去喝杯咖啡吧 :)
### c. 建立地圖 ([Reference](https://github.com/ethz-asl/maplab/wiki/Running-ROVIOLI-in-VIO-mode))
**1. 收集資料**
首先, 一邊移動一邊錄製一段包含imu和camera資訊的bag檔, 建議記錄的路徑為首尾相連。 注意在錄製的過程中要儘量避免裝置突然大幅度晃動的情況。 **官方建議的 imu sample rate 為 200Hz, camera 的 frame rate 為 20Hz。**
**2. 準備校正檔案**
在使用maplab的工具建立地圖前, 需要準備以下文件。 文件的生成請參照kalibr的教學部份。
* ncamera.yaml: imu-camera的校正檔案, 可將kalibr產生的校正檔透過kalibr的工具轉換成maplab使用的格式。 ([格式參考](https://github.com/ethz-asl/maplab/blob/master/applications/rovioli/share/ncamera-euroc.yaml))
* imu_parameters_maplab.yaml: imu的校正資料。 ([格式參考](https://github.com/ethz-asl/maplab/blob/master/applications/rovioli/share/imu-adis16488.yaml))
* imu_parameters_rovio.yaml: imu的校正資料,格式與imu_maplab.yaml略有不同。([格式參考](https://github.com/ethz-asl/maplab/blob/master/applications/rovioli/share/imu-sigmas-rovio.yaml))
想要將kalibr產生的校正檔轉換成maplab使用的格式,只要簡單地執行kalibr的工具即可,命令如下:
```cmd
rosrun kalibr kalibr_maplab_config --to-ncamera \
--label <your_label> \
--cam <your_cam_chain_yaml>
```
其中 <your_label> 是產生的校正檔的內部名稱,基本上不會產生影響。
<your_cam_chain_yaml> 則是 kalibr 產生的 .yaml 檔名
**3. 使用bag檔建立地圖**
建立一個啟動maplab校正工具的腳本 build.sh, 可參考以下範例:
```sh
#!/usr/bin/env bash
LOCALIZATION_MAP_OUTPUT=$1
ROSBAG=$2
NCAMERA_CALIBRATION="ncamera.yaml"
IMU_PARAMETERS_MAPLAB="imu_parameters_maplab.yaml"
IMU_PARAMETERS_ROVIO="imu_parameters_rovio.yaml"
REST=$@
rosrun rovioli rovioli \
--alsologtostderr=1 \
--v=2 \
--ncamera_calibration=$NCAMERA_CALIBRATION \
--imu_parameters_maplab=$IMU_PARAMETERS_MAPLAB \
--imu_parameters_rovio=$IMU_PARAMETERS_ROVIO \
--datasource_type="rosbag" \
--save_map_folder="$LOCALIZATION_MAP_OUTPUT" \
--optimize_map_to_localization_map=false \
--map_builder_save_image_as_resources=false \
--datasource_rosbag=$ROSBAG $REST
```
註:
```sh
# Use this flag to remove (or change) the suffix (default: image_raw) from the camera topic.
--vio_camera_topic_suffix=""
```
前置準備完成後, 創建一個資料夾並把所有檔案複製進去, 可以參考下列配置。

接著啟動工具。 執行時的畫面如下圖, 可以另外打開rviz觀察地圖的建立情形。(注意此地圖還不是最佳化的地圖)
```cmd
roscore&
./build.sh map data.bag
```

**2. 利用topic建立地圖**
也可以說是real-time建立地圖。 要稍微修改build.sh的內容:
```sh
#!/usr/bin/env bash
LOCALIZATION_MAP_OUTPUT=$1
ROSBAG=$2
NCAMERA_CALIBRATION="ncamera.yaml"
IMU_PARAMETERS_MAPLAB="imu_parameters_maplab.yaml"
IMU_PARAMETERS_ROVIO="imu_parameters_rovio.yaml"
REST=$@
rosrun rovioli rovioli \
--alsologtostderr=1 \
--v=2 \
--ncamera_calibration=$NCAMERA_CALIBRATION \
--imu_parameters_maplab=$IMU_PARAMETERS_MAPLAB \
--imu_parameters_rovio=$IMU_PARAMETERS_ROVIO \
--datasource_type="rostopic" \
--save_map_folder="$LOCALIZATION_MAP_OUTPUT" \
--optimize_map_to_localization_map=false \
--map_builder_save_image_as_resources=false \
```
執行工具使用的指令如下:
```cmd
../build.sh map
```
### e. 地圖最佳化 ([Reference](https://github.com/ethz-asl/maplab/wiki/Preparing-a-multi-session-map))
**1. 啟動介面**
開啟一個新的terminal, 移動到maplab所在的workspace並初始環境,接者執行maplab console
```cmd
cd ~/maplab_ws
source ~/maplab_ws/devel/setup.bash
roscore & rosrun maplab_console maplab_console
```
成功執行的話terminal會顯示maplab的初始介面畫面

**2. 載入地圖**
進入介面後, 首先我們需要把建立好的地圖先載入
```
load --map_folder <path/to/the/downloaded/map>
```
載入成功的話會出現以下結果

想要觀察地圖, 先打開rviz, 再在maplab console使用指令 `v`
**3. 最佳化**
由實驗我們可以知道,由多個各自最佳化的地圖疊合再做最佳化可以得到最好的成果。
首先分別載入地圖並執行 `optvi` 已進行各自的最佳化。
結束後使用`save --map_folder <path/to/save/the/map> --overwrite`覆蓋原本的地圖或是另外儲存。
完成後, 使用以下指令載入要疊合的地圖
```
load_merge_all_maps --maps_folder <path/to/optimized/maps>
```
使用以下指令進行最佳化
```
sbk
aam
relax
kfh
lc
optvi
```
以下是兩張已最佳化的地圖疊合範例:
_i. 載入_

_ii. 經過aam_

_iii. 經過optvi_
