Skip to content
This repository has been archived by the owner on Dec 15, 2023. It is now read-only.

Commit

Permalink
Don't use imu_sampling_ratio option
Browse files Browse the repository at this point in the history
  • Loading branch information
minghongx committed May 7, 2023
1 parent 3f21ef9 commit c5034c7
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions params/lds_2d.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
-- https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html
-- https://github.com/ROBOTIS-GIT/turtlebot3/blob/master/turtlebot3_slam/config/turtlebot3_lds_2d.lua
-- https://github.com/jackal/jackal_cartographer_navigation/blob/melodic-devel/config/jackal.lua
-- ros2 bag record --all
-- ros2 run cartographer_ros cartographer_rosbag_validate -bag_filename <rosbag2_dir>

Expand Down Expand Up @@ -28,10 +29,11 @@ options = {
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 0.025, -- times 200 Hz equals 5 Hz
landmarks_sampling_ratio = 1.,
-- https://github.com/cartographer-project/cartographer/issues/1569#issuecomment-491468305
imu_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true
Expand Down

0 comments on commit c5034c7

Please sign in to comment.