cartographer-project / cartographer

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.
Apache License 2.0
7.03k stars 2.24k forks source link

Has anyone has seen this 'rotation' error before? #1615

Open joekeo opened 4 years ago

joekeo commented 4 years ago

I am testing the stability of some sensors and nodes in my robot, which means that i am leaving it on the spot for some while.

When the robot boots and makes the initial map, this is how it looks like: image But after a while keeping the robot still, the map seems to be rotated, looking like this: image Has anyone has come across this before? Any Ideas what is causing this behaviour?

garlinplus commented 4 years ago

how much is your yaw angle of your robot

joekeo commented 4 years ago

this is the .lua file:


include "map_builder.lua"
include "trajectory_builder.lua"

-- Cartographer_ros configuration reference:
-- https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "rs_t265_accel_frame",
  published_frame = "base_link",
  use_odometry = true,
  provide_odom_frame = true,
  odom_frame = "odom",
  publish_frame_projected_to_2d = false,
  use_pose_extrapolator = on,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  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 = 1.,
  landmarks_sampling_ratio = 1.,
}
--tunning guide
--https://google-cartographer-ros.readthedocs.io/en/latest/tuning.html

-- Cartographer configuration options:
-- https://google-cartographer.readthedocs.io/en/latest/configuration.html

MAP_BUILDER.use_trajectory_builder_2d = true

--Local Slam
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 25
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.min_range = 0
TRAJECTORY_BUILDER_2D.max_range = 30.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 30.1
TRAJECTORY_BUILDER_2D.max_z = .8
TRAJECTORY_BUILDER_2D.min_z = -.2

TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1e3 --default 1
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 100 --defualt 10
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 200 --default 40

TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 0.0001 --default 5.
TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 9.81 --default 10

--Optimisation parameters
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 10
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.num_threads = 4

TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1 --deafult 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(20.) --default 20.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 1e-1 --default 1e-1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1 --deafult 1e-1

TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.01 --default 0.025
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.min_num_points = 50 --default 100
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_length = 0.5 --default 0.5
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_range = 50 --default 50

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 20 -- default 90

--map output parameters

--Global Slam
--Setting POSE_GRAPH.optimize_every_n_nodes to 0 is a handy way
--to disable global SLAM and concentrate on the behavior of local SLAM.
--This is usually one of the first thing to do to tune Cartographer.
POSE_GRAPH.optimize_every_n_nodes = 10 --90 default

POSE_GRAPH.optimization_problem.huber_scale = 1e1 --default 1e1
POSE_GRAPH.optimization_problem.acceleration_weight = 1e3 --default 1e3
POSE_GRAPH.optimization_problem.rotation_weight = 3e5 --default 3e5
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 10 --default 1e5
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1 --deafult 1e5
POSE_GRAPH.optimization_problem.fixed_frame_pose_translation_weight = 1e-1 --default 1e1
POSE_GRAPH.optimization_problem.fixed_frame_pose_rotation_weight = 1e-1 --default 1e2
POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5 --default 1e5
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5 --default 1e5

POSE_GRAPH.constraint_builder.loop_closure_translation_weight = 1.1e5 --default 1.1e4
POSE_GRAPH.constraint_builder.loop_closure_rotation_weight = 1e6 --default 1e5
POSE_GRAPH.constraint_builder.max_constraint_distance = 30 --default 15.
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher.linear_search_window = 7. --default
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher.angular_search_window = math.rad(30.) --default math.rad(30.)
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher.branch_and_bound_depth = 7 --default 7

POSE_GRAPH.constraint_builder.ceres_scan_matcher.occupied_space_weight = 1e3 --default 20
POSE_GRAPH.constraint_builder.ceres_scan_matcher.translation_weight = 100 --default 10
POSE_GRAPH.constraint_builder.ceres_scan_matcher.rotation_weight = 200 --default 1
POSE_GRAPH.constraint_builder.ceres_scan_matcher.ceres_solver_options.num_threads = 4 --default
POSE_GRAPH.constraint_builder.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 30 --default 10

POSE_GRAPH.matcher_translation_weight = 5e2 --default 5e2

POSE_GRAPH.matcher_rotation_weight = 1.6e3 --default 1.6e3

--Optimisation parameters
MAP_BUILDER.num_background_threads = 4

POSE_GRAPH.global_sampling_ratio = 0.003 --default 0.003

POSE_GRAPH.constraint_builder.sampling_ratio = 0.3 --default 0.3
POSE_GRAPH.constraint_builder.min_score = 0.55 --default 0.55

POSE_GRAPH.global_constraint_search_after_n_seconds = 10 --default 10

POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 50 --default 50
POSE_GRAPH.optimization_problem.ceres_solver_options.num_threads = 7 --default 7

return options
nhphuong91 commented 4 years ago

I guess your IMU source for odometry is drifting quite fast. Cartographer accepts drifting in odometry data but not much. Try to use rviz to view tf between /odom and /base_link (or /base_footprint). My experience is that it would slowly and steadily rotate even though your robot is stand still.