ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The problem is that the "sync" dataset doesn't have exactly the same stamps for left and right images. You may copy the stamps from one timestamps.txt to all others so that the image/camera_info contained in the generated bag have the same stamps. Otherwise, we should set approx_sync
to true. I recommend to use rtabmap.launch
directly. Example for stereo:
$ roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start" approx_sync:=true use_sim_time:=true frame_id:=base_link
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
Bonus: you can also record the velodyne clouds at the same time:
$ roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start" approx_sync:=true use_sim_time:=true frame_id:=base_link rgbd_sync:=true approx_rgbd_sync:=true subscribe_scan_cloud:=true scan_cloud_topic:=/kitti/velo/pointcloud
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
cheers,
Mathieu
2 | No.2 Revision |
The problem is that the "sync" dataset doesn't have exactly the same stamps for left and right images. You may copy the stamps from one timestamps.txt to all others so that the image/camera_info contained in the generated bag have the same stamps. stamps (if so, use approx_sync:=true
and approx_rgbd_sync:=false
in examples below). Otherwise, we should set approx_sync
to true. I recommend to use rtabmap.launch
directly. Example for stereo:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" \
approx_sync:=true use_sim_time:=true \
use_sim_time:=true\
frame_id:=base_link
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
BonusVelodyne: you can also record the velodyne clouds at the same time:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=true \
approx_rgbd_sync:=true \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
IMU, Ground truth and GPS
First we need to modify TF /world -> /base_link
in the bag to /world -> /base_link_gt
. This can be done with a script like this (called filterTF.py
):
import rosbag
from tf.msg import tfMessage
with rosbag.Bag('kitti_2011_09_26_drive_0001_synced_out.bag', 'w') as outbag:
for topic, msg, t in rosbag.Bag('kitti_2011_09_26_drive_0001_synced.bag').read_messages():
if topic == "/tf" and msg.transforms:
newList = [];
for m in msg.transforms:
if m.header.frame_id == "world":
m.child_frame_id = "base_link_gt"
newList.append(m)
if len(newList)>0:
msg.transforms = newList
outbag.write(topic, msg, t)
else:
outbag.write(topic, msg, t)
Then:
$ python filterTF.py
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=false \
approx_rgbd_sync:=false \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud \
imu_topic:=/kitti/oxts/imu \
gps_topic:=/kitti/oxts/gps/fix \
wait_imu_to_init:=true \
ground_truth_frame_id:=world \
ground_truth_base_frame_id:=base_link_gt
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced_out.bag
cheers,
Mathieu
3 | No.3 Revision |
The problem is that the "sync" dataset doesn't have exactly the same stamps for left and right images. You may copy the stamps from one timestamps.txt to all others so that the image/camera_info contained in the generated bag have the same stamps (if so, use approx_sync:=true
and approx_rgbd_sync:=false
in examples below). Otherwise, we should set approx_sync
to true. I recommend to use rtabmap.launch
directly. Example for stereo:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true\
frame_id:=base_link
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
Velodyne: you can also record the velodyne clouds at the same time:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=true \
approx_rgbd_sync:=true \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
IMU, Ground truth and GPS
First we need to modify TF /world -> /base_link
in the bag to /world -> /base_link_gt
. This can be done with a script like this (called filterTF.py
):
import rosbag
from tf.msg import tfMessage
with rosbag.Bag('kitti_2011_09_26_drive_0001_synced_out.bag', 'w') as outbag:
for topic, msg, t in rosbag.Bag('kitti_2011_09_26_drive_0001_synced.bag').read_messages():
if topic == "/tf" and msg.transforms:
newList = [];
for m in msg.transforms:
if m.header.frame_id == "world":
m.child_frame_id = "base_link_gt"
newList.append(m)
if len(newList)>0:
msg.transforms = newList
outbag.write(topic, msg, t)
else:
outbag.write(topic, msg, t)
Then:
$ python filterTF.py
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start" rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=false \
approx_rgbd_sync:=false \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud \
imu_topic:=/kitti/oxts/imu \
gps_topic:=/kitti/oxts/gps/fix \
wait_imu_to_init:=true \
ground_truth_frame_id:=world \
ground_truth_base_frame_id:=base_link_gt
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced_out.bag
cheers,
Mathieu
4 | No.4 Revision |
The problem is that the "sync" dataset doesn't have exactly the same stamps for left and right images. You may copy the stamps from one timestamps.txt to all others so that the image/camera_info contained in the generated bag have the same stamps (if so, use approx_sync:=true
and approx_rgbd_sync:=false
in examples below). Otherwise, we should set approx_sync
to true. I recommend to use rtabmap.launch
directly. Example for stereo:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true\
frame_id:=base_link
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
Velodyne: you can also record the velodyne clouds at the same time:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=true \
approx_rgbd_sync:=true \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
IMU, Ground truth and GPS
First we need to modify TF /world -> /base_link
in the bag to /world -> /base_link_gt
. This can be done with a script like this (called filterTF.py
):
import rosbag
from tf.msg import tfMessage
with rosbag.Bag('kitti_2011_09_26_drive_0001_synced_out.bag', 'w') as outbag:
for topic, msg, t in rosbag.Bag('kitti_2011_09_26_drive_0001_synced.bag').read_messages():
if topic == "/tf" and msg.transforms:
newList = [];
for m in msg.transforms:
if m.header.frame_id == "world":
m.child_frame_id = "base_link_gt"
newList.append(m)
if len(newList)>0:
msg.transforms = newList
outbag.write(topic, msg, t)
else:
outbag.write(topic, msg, t)
Then:
$ python filterTF.py
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" 1 --Optimizer/GravitySigma 0.3" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=false \
approx_rgbd_sync:=false \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud \
imu_topic:=/kitti/oxts/imu \
gps_topic:=/kitti/oxts/gps/fix \
wait_imu_to_init:=true \
ground_truth_frame_id:=world \
ground_truth_base_frame_id:=base_link_gt
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced_out.bag
cheers,
Mathieu
5 | No.5 Revision |
The problem is that the "sync" dataset doesn't have exactly the same stamps for left and right images. You may copy the stamps from one timestamps.txt to all others so that the image/camera_info contained in the generated bag have the same stamps (if so, use
and approx_sync:=trueapprox_sync:=falseapprox_rgbd_sync:=false
in examples below). Otherwise, we should set approx_sync
to true. I recommend to use rtabmap.launch
directly. Example for stereo:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true\
frame_id:=base_link
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
Velodyne: you can also record the velodyne clouds at the same time:
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=true \
approx_rgbd_sync:=true \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced.bag
IMU, Ground truth and GPS
First we need to modify TF /world -> /base_link
in the bag to /world -> /base_link_gt
. This can be done with a script like this (called filterTF.py
):
import rosbag
from tf.msg import tfMessage
with rosbag.Bag('kitti_2011_09_26_drive_0001_synced_out.bag', 'w') as outbag:
for topic, msg, t in rosbag.Bag('kitti_2011_09_26_drive_0001_synced.bag').read_messages():
if topic == "/tf" and msg.transforms:
newList = [];
for m in msg.transforms:
if m.header.frame_id == "world":
m.child_frame_id = "base_link_gt"
newList.append(m)
if len(newList)>0:
msg.transforms = newList
outbag.write(topic, msg, t)
else:
outbag.write(topic, msg, t)
Then:
$ python filterTF.py
$ roslaunch rtabmap_ros rtabmap.launch \
stereo:="true" \
left_image_topic:=/kitti/camera_color_left/image_raw \
right_image_topic:=/kitti/camera_color_right/image_raw \
left_camera_info_topic:=/kitti/camera_color_left/camera_info \
right_camera_info_topic:=/kitti/camera_color_right/camera_info \
rtabmap_args:="--delete_db_on_start --Grid/CellSize 0.3 --Grid/ClusterRadius 1 --Optimizer/GravitySigma 0.3" \
approx_sync:=true \
use_sim_time:=true \
frame_id:=base_link \
rgbd_sync:=false \
approx_rgbd_sync:=false \
subscribe_scan_cloud:=true \
scan_cloud_topic:=/kitti/velo/pointcloud \
imu_topic:=/kitti/oxts/imu \
gps_topic:=/kitti/oxts/gps/fix \
wait_imu_to_init:=true \
ground_truth_frame_id:=world \
ground_truth_base_frame_id:=base_link_gt
$ rosbag play --clock kitti_2011_09_26_drive_0001_synced_out.bag
cheers,
Mathieu