Re: Slam using Intel RealSense tracking camera - T265
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Slam-using-Intel-RealSense-tracking-camera-T265-tp6333p7291.html
Updating example of this post for realsense ros V 2.40.0.
Using T265 odometry
# Start realsense2 (in odometry-only mode):
$ roscore
$ rosparam set /camera/tracking_module/enable_mapping false
$ roslaunch realsense2_camera rs_t265.launch enable_fisheye1:=true enable_fisheye2:=true
# Start the camera_info publishers with the stereo fisheye calibration files:
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_left.yaml \
image:=/camera/fisheye1/image_raw \
camera_info:=/camera/fisheye1/camera_info_calib
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_right.yaml \
image:=/camera/fisheye2/image_raw \
camera_info:=/camera/fisheye2/camera_info_calib
# Start RTAB-Map in stereo mode, use T265 odometry and do rectification:
$ roslaunch rtabmap_ros rtabmap.launch \
args:="-d --Rtabmap/ImagesAlreadyRectified false --Mem/UseOdomGravity true --Optimizer/GravitySigma 0.3" \
stereo:=true \
left_image_topic:=/camera/fisheye1/image_raw \
right_image_topic:=/camera/fisheye2/image_raw \
left_camera_info_topic:=/camera/fisheye1/camera_info_calib \
right_camera_info_topic:=/camera/fisheye2/camera_info_calib \
visual_odometry:=false \
odom_frame_id:=camera_odom_frame

Using F2M (RTAB-Map) odometry
You should have this
commit.
# Start realsense2 (disable pose estimation):
$ roscore
$ roslaunch realsense2_camera rs_t265.launch enable_pose:=false enable_fisheye1:=true enable_fisheye2:=true unite_imu_method:=linear_interpolation
# Compute IMU quaternion
$ rosrun imu_filter_madgwick imu_filter_node \
_use_mag:=false \
_publish_tf:=false \
_world_frame:="enu" \
/imu/data_raw:=/camera/imu \
/imu/data:=/rtabmap/imu
# Start the camera_info publishers with the stereo fisheye calibration files:
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_left.yaml \
image:=/camera/fisheye1/image_raw \
camera_info:=/camera/fisheye1/camera_info_calib
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_right.yaml \
image:=/camera/fisheye2/image_raw \
camera_info:=/camera/fisheye2/camera_info_calib
# Start RTAB-Map in stereo mode, with stereo rectification done by stereo_odometry:
$ roslaunch rtabmap_ros rtabmap.launch \
args:="-d" \
odom_args:="--Rtabmap/ImagesAlreadyRectified false --Optimizer/GravitySigma 0.3" \
stereo:=true \
left_image_topic:=/camera/fisheye1/image_raw \
right_image_topic:=/camera/fisheye2/image_raw \
left_camera_info_topic:=/camera/fisheye1/camera_info_calib \
right_camera_info_topic:=/camera/fisheye2/camera_info_calib \
use_odom_features:=true \
wait_imu_to_init:=true \
imu_topic:=/rtabmap/imu

Using F2M (RTAB-Map) odometry but with T265 odometry as guess
You should have this
commit.
# Start realsense2 (in odometry-only mode):
$ roscore
$ rosparam set /camera/tracking_module/enable_mapping false
$ roslaunch realsense2_camera rs_t265.launch enable_fisheye1:=true enable_fisheye2:=true unite_imu_method:=linear_interpolation
# Compute IMU quaternion
$ rosrun imu_filter_madgwick imu_filter_node \
_use_mag:=false \
_publish_tf:=false \
_world_frame:="enu" \
/imu/data_raw:=/camera/imu \
/imu/data:=/rtabmap/imu
# Start the camera_info publishers with the stereo fisheye calibration files:
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_left.yaml \
image:=/camera/fisheye1/image_raw \
camera_info:=/camera/fisheye1/camera_info_calib
$ python camera_info_pub.py \
_url:=/home/mathieu/Documents/RTAB-Map/camera_info/905312112011_right.yaml \
image:=/camera/fisheye2/image_raw \
camera_info:=/camera/fisheye2/camera_info_calib
# Start RTAB-Map in stereo mode, with stereo rectification done by stereo_odometry:
$ roslaunch rtabmap_ros rtabmap.launch \
args:="-d" \
odom_args:="--Rtabmap/ImagesAlreadyRectified false --Optimizer/GravitySigma 0.3" \
stereo:=true \
left_image_topic:=/camera/fisheye1/image_raw \
right_image_topic:=/camera/fisheye2/image_raw \
left_camera_info_topic:=/camera/fisheye1/camera_info_calib \
right_camera_info_topic:=/camera/fisheye2/camera_info_calib \
odom_guess_frame_id:=camera_odom_frame \
use_odom_features:=true \
wait_imu_to_init:=true \
imu_topic:=/rtabmap/imu