introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
1.01k stars 558 forks source link

Loop closure detection is not work with 2d Lidar #652

Open NamDinhRobotics opened 3 years ago

NamDinhRobotics commented 3 years ago

Hi Rtabmap author, I used the demo_mapping.bag file, I run SLAM mode as in section 3.2( I used only 2D Lidar), in this link: http://wiki.ros.org/rtabmap_ros After that, I re-run the localization mode, But it could not detect loop closure using only 2D Lidar. Would you guess the problem with loop closure using only 2D lidar? Ofcouse, when I run with laser and RGB-D image, it worked well for slam and localization mode Would you give any recommend for only 2D laser localization mode? Thanks,

matlabbe commented 3 years ago

Hi, rtabmap cannot do global localization with only lidar. However, if the robot is restarting in localization mode at the last pose recorded in the previous session, it will able to locally localize with the map. When you replay the bag in localization mode, the robot doesn't restart at the last pose of the previous session. I tested the demo without camera by changing this: https://github.com/introlab/rtabmap_ros/blob/1ecce1587845ce8383de09ff8640e07ec1127974/launch/demo/demo_robot_mapping.launch#L26-L27 by this:

      <param name="subscribe_depth" type="bool" value="false"/>
      <param name="subscribe_rgb" type="bool" value="false"/>
      <param name="subscribe_scan"  type="bool" value="true"/>

I did a first mapping, then relaunched with localization:=true. While moving, it may be very wrong: Screenshot from 2021-10-01 12-35-50

What you can do is to edit 2D Pose Estimate topic for /rtabmap/initialpose, then drag and drop a 2D pose estimate around the right place: Screenshot from 2021-10-01 12-36-15

The robot will register more accurately the coarse estimated position set manually: Screenshot from 2021-10-01 12-36-36

Another approach would be to save the map using map_server map_saver, then relaunch with AMCL:

# to save map
$ rosrun map_server map_saver map:=/rtabmap/grid_map

# localization
$ roscore
$ rosparam set use_sim_time true
$ rosrun map_server map_server map.yaml
$ rosrun amcl amcl scan:=/jn0/base_scan
$ rviz
$ rosbag play --clock demo_mapping.bag

With AMCL, you can also set a 2D Pose Estimate with /initialpose topic. You can show the particles of AMCL with topic particlecloud to see what it is estimating, which is a PoseArray msg. Looking the AMCL parameters, there are some to spread particles on larger area in case you want to localize on start everywhere in the map.

cheers, Mathieu

NamDinhRobotics commented 3 years ago

Great answer, I will try following your suggestions,

Thank you so much, Mathieu