iris-ua / iris_lama_ros

LaMa on ROS
BSD 3-Clause "New" or "Revised" License
208 stars 59 forks source link

can not save closed loop map #53

Closed ZOUJIASHUAI closed 1 year ago

ZOUJIASHUAI commented 1 year ago

hello @eupedrosa rviz seems has detected close loop ,but the map didn't fix the drift,I used map_server to save the map,but the result still didn't fix the drift . 微信图片_20220909162605

eupedrosa commented 1 year ago

There may be a failure in the loop closure. Are you using the default parameters? What type of laser do you have?

Try adding to your rosrun _key_pose_distance:=0.5 and _loop_closure_scan_rmse:=0.1

eupedrosa commented 1 year ago

Maybe it was not a failure and you just need to make you robot move a little more to trigger the optimization. The optimization is lazy, it only optimizes after getting at least 5 new links or has travelled for 15 meters.

Maybe I can force an optimization when the map is requested.

Alternative, if you are running from a rosbag you can do rosrun iris_lama_ros graph_slam2d_ros _rosbag:=/path/to/your/bag, it will force an optimization at the end.

ZOUJIASHUAI commented 1 year ago

hello @eupedrosa this is the bag I record,please test it , https://drive.google.com/file/d/1hSO3yzVccfd-W_FtjzkEwWeJ2ku3t8Za/view?usp=sharing

the tf tree is odom->base_link->laser

I combine two sick nano scan3 as one 360degree laser, the laser topic is /scan odom topic is /odom(also public in tf) imu topic is /imu/data(not used in iris)

I used rosrun map_server map_saver -f ~/1 to save map to get the 0.02res map,below is my param set,but seems still I can not get the loop closed map.

GraphSlam2D::Options options;
pnh_.param("d_thresh",   options.trans_thresh, 0.01);
pnh_.param("a_thresh",   options.rot_thresh,   0.01);
pnh_.param("l2_max",     options.l2_max,        0.01);
pnh_.param("resolution", options.resolution,   0.02);
pnh_.param("strategy",   options.strategy, std::string("lm"));

pnh_.param("key_pose_distance",         options.key_pose_distance, 1.0);
pnh_.param("key_pose_angular_distance", options.key_pose_angular_distance, 5 * M_PI);
pnh_.param("key_pose_head_delay",       options.key_pose_head_delay, 3);

pnh_.param("loop_search_max_distance", options.loop_search_max_distance, 15.0);
pnh_.param("loop_search_min_distance", options.loop_search_min_distance,  0.1);
pnh_.param("loop_closure_scan_rmse",   options.loop_closure_scan_rmse,   0.1);
pnh_.param("loop_max_candidates",      options.loop_max_candidates,         5);
pnh_.param("ignore_n_chain_poses",     options.ignore_n_chain_poses,       5);

options.max_iter = pnh_.param("max_iterations", 100);
options.patch_size = pnh_.param("patch_size",  32);

pnh_.param("mrange",    max_range_, 40.0);
eupedrosa commented 1 year ago

Hi there,

This is the map that I got using the default parameters but with resolution at 0.02:

graph_slam_map

The defaults parameters are:

    GraphSlam2D::Options options;
    pnh_.param("d_thresh",   options.trans_thresh, 0.01);
    pnh_.param("a_thresh",   options.rot_thresh,   0.25);
    pnh_.param("l2_max",     options.l2_max,        0.5);
    pnh_.param("resolution", options.resolution,   0.05); // _resolution:=0.02
    pnh_.param("strategy",   options.strategy, std::string("gn"));

    pnh_.param("key_pose_distance",         options.key_pose_distance, 1.0);
    pnh_.param("key_pose_angular_distance", options.key_pose_angular_distance, 0.5 * M_PI);
    pnh_.param("key_pose_head_delay",       options.key_pose_head_delay, 3);

    pnh_.param("loop_search_max_distance", options.loop_search_max_distance, 15.0);
    pnh_.param("loop_search_min_distance", options.loop_search_min_distance,  5.0);
    pnh_.param("loop_closure_scan_rmse",   options.loop_closure_scan_rmse,   0.05);
    pnh_.param("loop_max_candidates",      options.loop_max_candidates,         5);
    pnh_.param("ignore_n_chain_poses",     options.ignore_n_chain_poses,       20);

The mapping did failed with your parameters. The parameter l2_map is recomended to always be 0.5. It defines the "attraction" distance of the scan matching. A value of 0.01 is very low.

The loop_search_min_distance defines the minimum search radius for loop closure candidates and it will increate up to the loop_search_max_distance while no valid candidate is found. Once a valid candidate is found the search radius is set back to the loop_search_min_distance. Using a value of 0.1 is not recomended. It tells the system to start searching at a range of loop_search_min_distance.

I think there is also room for improving the default parameters, for example d_thresh is unnecessarily low. I can be set to 0.25 or even higher when you have a good laser and reasonable odometry.

Using this command $ rosrun iris_lama_ros graph_slam2d_ros _rosbag:=$PWD/2022.bag _resolution:=0.02 _map_publish_period:=0 _d_thresh:=0.25 _a_thresh:=0.25 _loop_closure_scan_rmse:=0.05 _key_pose_distance:=1.0 _mrange:=40 your map will be quickly created. You can try different parameters until you get a satisfatory result.