Hi Alex,
See this
page to track single RGB camera against a map previously built by a rgbd-d or stereo camera.
If you have an external odometry approach and assuming you are under ROS, then you can indeed use rtabmap node in localization mode with settings in the link above, but with odometry input set from your odometry node. Make sure to update the code to get this
commit. Here is a small example using an hand-held kinect:
1- Create the map
$ roslaunch freenect_launch freenect.launch depth_registration:=true
$ roslaunch rtabmap_ros rtabmap.launch \
args:="-d --Kp/DetectorStrategy 6 --Kp/MaxFeatures 1000 --Rtabmap/DetectionRate 0"
2- Just kill rtabmap.launch
3- Localize with RGB camera, here we still use rgbd_odometry to get odometry, but rtabmap node only subscribes to RGB image and localizes against pre-built map (default ~/.ros/rtabmap.db):
# External odometry
$ rosrun rtabmap_ros rgbd_odometry \
rgb/image:=/camera/rgb/image_rect_color \
depth/image:=/camera/depth_registered/image_raw \
rgb/camera_info:=/camera/rgb/camera_info \
_frame_id:=camera_link
# RTAB-Map
$ rosrun rtabmap_ros rtabmap \
--Kp/DetectorStrategy 6 \
--Kp/MaxFeatures 1000 \
--Rtabmap/DetectionRate 0 \
--Mem/IncrementalMemory false \
rgb/image:=/camera/rgb/image_rect_color \
rgb/camera_info:=/camera/rgb/camera_info \
odom:=odom \
_frame_id:=camera_link \
_subscribe_depth:=false
# Visualization
$ rosrun rtabmap_ros rtabmapviz _frame_id:=camera_link
cheers,
Mathieu