Skip to content

Commit

Permalink
[graph_slam] Update defaults.
Browse files Browse the repository at this point in the history
  • Loading branch information
eupedrosa committed Oct 4, 2022
1 parent 6547bae commit d6c004a
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 5 deletions.
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -96,12 +96,13 @@ Particle Filter SLAM only:
* `~srt`: Odometry error in translation as a function of rotation (default: 0.1).

Graph SLAM only:
* `~key_pose_distance`: Traveled distance to accumulate before creating a key pose (default: 1.0)
* `~d_thresh`: Traveled distance to accumulate before updating (default: 0.25 meters).
* `~key_pose_distance`: Traveled distance to accumulate before creating a key pose (default: 0.5)
* `~key_pose_angular`: Angular motion to accumulate before creating a key pose (default: PI/2)
* `~key_pose_head_delay`: Number of latest key poses to ignore for head key pose reference (default: 3)
* `~loop_search_max_distance`: Maximum distance used in the adaptive search of a loop candidate (default: 15.0)
* `~loop_search_min_distance`: Mininum distance used in the adaptive search of a loop candidate (default: 5.0)
* `-loop_closure_scan_rmse`: Maximum RMSE (root mean-squared-error) allowed for a loop candidate (default: 0.05). Increase this value if loop closure links are not being created properly. A good value would be 0.1. Beware of false positives when this value too high.
* `-loop_closure_scan_rmse`: Maximum RMSE (root mean-squared-error) allowed for a loop candidate (default: 0.075). Increase this value if loop closure links are not being created properly. A good value would be 0.1. Beware of false positives when this value too high.
* `~loop_max_candidates`: Maximum number of candidates considered for loop closure (default: 5)
* `~ignore_n_chain_poses`: Number of the lastest key poses to ignore for loop closure (default: 20)

Expand Down
6 changes: 3 additions & 3 deletions src/graph_slam2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,19 +59,19 @@ lama::GraphSlam2DROS::GraphSlam2DROS()
Pose2D prior(pos, tmp);

GraphSlam2D::Options options;
pnh_.param("d_thresh", options.trans_thresh, 0.01);
pnh_.param("d_thresh", options.trans_thresh, 0.25);
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);
pnh_.param("strategy", options.strategy, std::string("gn"));

pnh_.param("key_pose_distance", options.key_pose_distance, 1.0);
pnh_.param("key_pose_distance", options.key_pose_distance, 0.5);
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_closure_scan_rmse", options.loop_closure_scan_rmse, 0.075);
pnh_.param("loop_max_candidates", options.loop_max_candidates, 5);
pnh_.param("ignore_n_chain_poses", options.ignore_n_chain_poses, 20);

Expand Down

0 comments on commit d6c004a

Please sign in to comment.