reproducing MIT sata dataset result JFR18

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

reproducing MIT sata dataset result JFR18

alexr
Hi Mathieu,

How can I reproduce the MIT sata dataset as presented in JFR18 paper. There are a set of instructions in the demo folder however, its not that clear. Do you have a step by step guide to reproduce the result.

Thanks

Alex
------ Alex
Reply | Threaded
Open this post in threaded view
|

Re: reproducing MIT sata dataset result JFR18

matlabbe
Administrator
Hi,

Which version do you want to try? Lidar SLAM or RGB-D SLAM or Stereo SLAM? If I take the launch_lidar example, with Long-Range Lidar S2M configuration (and RGB-D for loop closure detection) of Table 8 of this paper "RTAB-Map as an Open-Source Lidar and Visual SLAM Library for Large-Scale and Long-Term Online Operation":

$ roslaunch rtabmap_ros rtabmap.launch \
  args:="-d \
    --Reg/Force3DoF true \
    --Reg/Strategy 1 \
    --RGBD/ProximityPathMaxNeighbors 10 \
    --Mem/STMSize 30 \
    --Mem/LaserScanVoxelSize 0.05 \
    --Mem/LaserScanNormalK 5 \
    --Mem/LaserScanNormalRadius 1 \
    --Icp/Epsilon 0.001 \
    --Icp/MaxTranslation 0.5 \
    --Icp/PM true \
    --Grid/RangeMax 0" \
  odom_args:="\
    --Icp/VoxelSize 0.05 \
    --Icp/PointToPlaneRadius 1"  \
  rgbd_sync:=true \
  subscribe_scan:=true \
  frame_id:=base_footprint \
  ground_truth_frame_id:=world \
  ground_truth_base_frame_id:=scan_gt \
  use_sim_time:=true \
  odom_guess_frame_id:=odom_combined \
  odom_guess_min_translation:=0.1 \
  odom_guess_min_rotation:=0.1 \
  odom_topic:=odom \
  icp_odometry:=true \
  visual_odometry:=false \
  scan_topic:=/base_scan_t \
  rgb_topic:=/camera/rgb/image_raw \
  depth_topic:=/camera/depth/image_raw \
  camera_info_topic:=/camera/rgb/camera_info

$ ./republish_scan.py _offset:=82.2

$ ./gt_tf_broadcaster.py _file:=./stata-mit/2012-01-25-12-14-25_part1_floor2.gt.laser.poses _frame_id:=scan_gt _fixed_frame_id:=world _offset_time:=82.2 _offset_x:=-0.275

$ rosbag play --clock --pause ./stata-mit/2012-01-25-12-14-25.bag


Note that rtabmap should be built with libpointmatcher to get similar results than in the paper. I don't have the bag to test this right now, let me know if you have problems running it.

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

Re: reproducing MIT sata dataset result JFR18

alexr
Hi

Thanks a lot.

Alex
------ Alex