RTAB-Map and COLMAP

classic Classic list List threaded Threaded
7 messages Options
Reply | Threaded
Open this post in threaded view
|

RTAB-Map and COLMAP

huan_c
Hi everyone,

I,m using RTAB-Map and I'm trying to export the poses and use them in COLMAP, but the origin is different, in adittion, the poses from COLMAP are 1-N image referenced. Is there any way to play with this poses exportation?

Thanks in advance.
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

matlabbe
Administrator
Hi,

In rtabmap-databaseViewer, to extract images with ID:

File-> Extract Images... , select Id

to extract poses in camera frame (which is often used in SFM frameworks), x->right, y->down, z->forward:

File -> Export Poses, select RGBD SLAM with ID to know the correspondences with the images extracted, select current Map Graph view, select Camera frame.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

FooTheBar
Is there also a way to pass the optimized poses from COLMAP into RTAB-Map and then generate a map/Database with RTAB? (like using an odometry with infine weight or nor running the pose-graph optimization at all?)
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

matlabbe
Administrator
If IDs are matching between the new optimized poses and nodes in the database, the "simpliest" way would be to update opt_ids and opt_poses fields in the database directly. A python script with sqlite3 could be a way to implement this (this script can be used to compress and uncompress the opt_poses blob).

If the modified database is used in localization mode, it should keep the modified poses.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

PLAN8
In reply to this post by FooTheBar
Hi, I'm also very keen to figure out this pipeline in order to try using RTAB for Gaussian Splatting software.

I haven't figured out how to import any of the exported data into COLMAP, any chance you could explain how you go about getting the camera poses and sparse cloud into Colmap GUI please?

Thank you!
yb
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

yb
This post was updated on .
This topic may be outdated. I've recently been trying to combine rtabmap and colmap. I'm inputting the poses calculated by rtabmap as known data into colmap. Here's my current approach: 1. Use this command to export camera poses and RGB maps from the rtabmap database.
rtabmap-export --poses --images  --database test.db
2.Process the resulting pose.txt file, including converting the coordinate system to the colmap coordinate system and converting the file to the colmap's images.txt format. I used a script like this for the conversion.
import os
import numpy as np
from scipy.spatial.transform import Rotation as R

pose_file = "/home/ubuntu/merge/merge_poses.txt"
img_dir = "/home/ubuntu/merge/merge_rgb"

images = sorted(os.listdir(img_dir))

os.makedirs("/home/ubuntu/merge/sparse_init", exist_ok=True)
fout = open("/home/ubuntu/merge/sparse_init/images.txt", "w")

with open(pose_file, "r") as f:
    for idx, line in enumerate(f):
        line = line.strip()
        
        if not line or line.startswith('#'):
            continue
            
        vals = list(map(float, line.split()))
        if len(vals) < 9:
            continue

        _, tx, ty, tz, qx, qy, qz, qw, _ = vals

        R_mb = R.from_quat([qx, qy, qz, qw]).as_matrix()
        t_mb = np.array([tx, ty, tz])

        # ----- base_link -> camera_optical (from local_transform) -----
        R_bc = np.array([
            [ 0.,  0.,  1.],
            [-1.,  0.,  0.],
            [ 0., -1.,  0.]
        ])
        t_bc = np.zeros(3)

        # ----- map -> camera -----
        R_mc = R_mb @ R_bc
        t_mc = R_mb @ t_bc + t_mb

        # ----- COLMAP needs camera -> world -----
        R_cw = R_mc.T
        t_cw = -R_cw @ t_mc

        q = R.from_matrix(R_cw).as_quat()  # x y z w

        image_name = images[idx]

        fout.write(
            f"{idx+1} {q[3]} {q[0]} {q[1]} {q[2]} "
            f"{t_cw[0]} {t_cw[1]} {t_cw[2]} 1 {image_name}\n\n"
        )

fout.close()

3. Then you need to obtain the camera parameters from the camera's YAML and organize them according to the colmap format.
4. Create a sparse folder, rename the pose.txt file to images.txt, and put it in along with the cameras.txt file containing the camera parameters. Create a blank point3D file.
5. Reconstruct the model according to the section on "Reconstruct sparse/dense model from known camera poses" in the colmap documentation. https://colmap.github.io/faq.html#reconstruct-sparse-dense-model-from-known-camera-poses
For reference only. Please point out any errors or omissions.
edit:Perhaps we should find a way to import the rtabmap points into colmap instead of rerunning the sparse reconstruction process...
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map and COLMAP

matlabbe
Administrator
Hi, thanks sharing how you export to colmap.

Small comments:

For 1., you may be able to export with "--poses_camera" argument instead to get the poses in camera optical frame already (map -> optical frame), so that you don't need to transform it in the conversion script in 2.

For the 3D points, if the format for each 3D point a 3D position and a list of 2D references from frames looking at that feature, it sounds like it could be the input and/or output of a Bundle Adjustment. The 3D points and 2D references could be returned in the main loop of rtabmap-export by calling this variant of the same function called in the main loop here. Then we get these:
std::map<int, cv::Point3f> points3DMap
std::map<int, std::map<int, FeatureBA> > wordReferences
However, I don't know if colmap would expect no outliers in that data, if so, using that data may not work because it is before doing bundle adjustment. I checked in OptimizerG2O, and there is a list of outliers, but only 3D points outliers, the 2D reference outliers are not tracked (which I think we should do instead, I'll create an issue about that EDIT: here).

So for now, maybe better sending blank points to colmap so that it recomputes them.

cheers,
Mathieu